diff --git a/.gitignore b/.gitignore index 5790b30e3cd..a1f0fdfba78 100644 --- a/.gitignore +++ b/.gitignore @@ -38,6 +38,7 @@ build/ *CodeLitePreProcessor.txt .aria2c.input .codelite +.debug .gdb_history .gtest .idea diff --git a/CHANGELOG.md b/CHANGELOG.md index 9334b0fef16..0d2efc8e9ef 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -4,6 +4,14 @@ * Improved the turning behavior of vehicles controlled by the TrafficManager, making them smoother. * Added a hybrid solid-state LiDAR with adjustable parameters (blueprint attributes) * Fix OpenDrive Builder lane width + * Introduced geom::AngularVelocity, geom::Velocity, geom::Acceleration, geom::Quaternion types + * Fixed geom::Rotation::RotateVector() rotation directions of pitch and roll + * Internal source code reorganizations to prepare extended ROS2 support + * ROS2Native: Extended functionality and performance of ROS2 support + * Introduced fine grained ServerSynchronization mechanism: each client decides for its own if it requires synchronization or not and provides its own synchronization window. + Be aware: some existing code using master/slave sync mechanism might need rework. See also generate_traffic.py. + + ## CARLA 0.9.16 diff --git a/Docs/ref_sensors.md b/Docs/ref_sensors.md index 9bbfed61b5e..4410fe8c8a8 100644 --- a/Docs/ref_sensors.md +++ b/Docs/ref_sensors.md @@ -1087,7 +1087,7 @@ The function the user has to call every time to send a message. This function ne - **Parameters:** - `data` (_function_) - The called function with one argument containing the sensor data. -The custom V2X message sensor works a little bit different than other sensors, because it has the *send* function in addition to the *listen* function, that needs to be called, before another sensor of this type will receive anything. The transmission of a custom message is only triggered, when *send* is called. Each message given to the *send* function is only transmitted once to all Custom V2X Message sensors currently spawned. +The custom V2X message sensor works a little bit different than other sensors, because it has the *send* function in addition to the *listen* function, that needs to be called, before another sensor of this type will receive anything. The transmission of a custom message is only triggered, when *send* is called. Each message given to the *send* function is only transmitted once to all Custom V2X Message sensors currently spawned. Independent communcation channels can be created by the sensors 'channel_id' attribute. Only sensors having the same 'channel_id' are communicating with each other. This allows to create different sender/receiver groups within the system. Example: @@ -1099,6 +1099,7 @@ Example: | Blueprint attribute | Type | Default | Description | |-------------------------|--------|-------------------------|------------------------------------| +| channel\_id | string | '' | Only Sender/Receiver with the same channel_id are communicating with each other | | transmit\_power | float | 21.5 | Sender transmission power in dBm | | receiver\_sensitivity | float | -99 | Receiver sensitivity in dBm | | frequency\_ghz | float | 5.9 | Transmission frequency in GHz. 5.9 GHz is standard for several physical channels. | diff --git a/Examples/CppClient/Makefile b/Examples/CppClient/Makefile index b75ff9e1ff3..bef9ab8839a 100644 --- a/Examples/CppClient/Makefile +++ b/Examples/CppClient/Makefile @@ -4,9 +4,9 @@ BINDIR=$(CURDIR)/bin INSTALLDIR=$(CURDIR)/libcarla-install TOOLCHAIN=$(CURDIR)/ToolChain.cmake -CC=/usr/bin/gcc-9 -CXX=/usr/bin/g++-9 -CXXFLAGS=-std=c++14 -pthread -fPIC -O3 -DNDEBUG -Werror -Wall -Wextra +CC=/usr/bin/gcc +CXX=/usr/bin/g++ +CXXFLAGS=-std=c++17 -pthread -fPIC -O3 -DNDEBUG -Werror -Wall -Wextra define log @echo "\033[1;35m$(1)\033[0m" diff --git a/Examples/CppClient/main.cpp b/Examples/CppClient/main.cpp index 4a69b2850f0..f624aa5e736 100644 --- a/Examples/CppClient/main.cpp +++ b/Examples/CppClient/main.cpp @@ -6,8 +6,8 @@ #include #include -#include -#include +#include +#include #include #include #include diff --git a/LibCarla/cmake/CMakeLists.txt b/LibCarla/cmake/CMakeLists.txt index d876d72b6d9..e1ede8f3d06 100644 --- a/LibCarla/cmake/CMakeLists.txt +++ b/LibCarla/cmake/CMakeLists.txt @@ -4,10 +4,12 @@ project(libcarla) option(LIBCARLA_BUILD_DEBUG "Build debug configuration" ON) option(LIBCARLA_BUILD_RELEASE "Build release configuration" ON) option(LIBCARLA_BUILD_TEST "Build unit tests" ON) +option(LIBCARLA_USE_ROS "Build ROS variant" OFF) message(STATUS "Build debug: ${LIBCARLA_BUILD_DEBUG}") message(STATUS "Build release: ${LIBCARLA_BUILD_RELEASE}") message(STATUS "Build test: ${LIBCARLA_BUILD_TEST}") +message(STATUS "Enable ROS: ${LIBCARLA_USE_ROS}") set(libcarla_source_path "${PROJECT_SOURCE_DIR}/../source") set(libcarla_source_thirdparty_path "${libcarla_source_path}/third-party") @@ -24,14 +26,12 @@ if (CMAKE_BUILD_TYPE STREQUAL "Client") elseif (CMAKE_BUILD_TYPE STREQUAL "Server") add_subdirectory("server") elseif (CMAKE_BUILD_TYPE STREQUAL "Pytorch") -add_subdirectory("pytorch") -elseif (CMAKE_BUILD_TYPE STREQUAL "ros2") -add_subdirectory("fast_dds") + add_subdirectory("pytorch") else () message(FATAL_ERROR "Unknown build type '${CMAKE_BUILD_TYPE}'") endif () # GTest is not compiled on Windows. -if ((LIBCARLA_BUILD_TEST) AND (NOT WIN32) AND (NOT (CMAKE_BUILD_TYPE STREQUAL "Pytorch")) AND (NOT (CMAKE_BUILD_TYPE STREQUAL "ros2"))) +if ((LIBCARLA_BUILD_TEST) AND (NOT WIN32) AND (NOT (CMAKE_BUILD_TYPE STREQUAL "Pytorch"))) add_subdirectory("test") endif() diff --git a/LibCarla/cmake/client/CMakeLists.txt b/LibCarla/cmake/client/CMakeLists.txt index f7461f291ed..168e4d90125 100644 --- a/LibCarla/cmake/client/CMakeLists.txt +++ b/LibCarla/cmake/client/CMakeLists.txt @@ -98,6 +98,12 @@ file(GLOB libcarla_carla_sources set(libcarla_sources "${libcarla_sources};${libcarla_carla_sources}") install(FILES ${libcarla_carla_sources} DESTINATION include/carla) +file(GLOB libcarla_carla_actors_sources + "${libcarla_source_path}/carla/actors/*.cpp" + "${libcarla_source_path}/carla/actors/*.h") +set(libcarla_sources "${libcarla_sources};${libcarla_carla_actors_sources}") +install(FILES ${libcarla_carla_actors_sources} DESTINATION include/carla/actors) + file(GLOB libcarla_carla_client_sources "${libcarla_source_path}/carla/client/*.cpp" "${libcarla_source_path}/carla/client/*.h") diff --git a/LibCarla/cmake/fast_dds/CMakeLists.txt b/LibCarla/cmake/fast_dds/CMakeLists.txt deleted file mode 100644 index 366549eefaf..00000000000 --- a/LibCarla/cmake/fast_dds/CMakeLists.txt +++ /dev/null @@ -1,60 +0,0 @@ -cmake_minimum_required(VERSION 3.5.1) -project(libcarla_fastdds) - -# Install headers. - -file(GLOB libcarla_carla_fastdds_headers - "${libcarla_source_path}/carla/ros2/*.h" - "${libcarla_source_path}/carla/ros2/publishers/*.h" - "${libcarla_source_path}/carla/ros2/subscribers/*.h" - "${libcarla_source_path}/carla/ros2/listeners/*.h" - "${libcarla_source_path}/carla/ros2/types/*.h" - ) -install(FILES ${libcarla_carla_fastdds_headers} DESTINATION include/carla/ros2) - -file(GLOB fast_dds_dependencies "${FASTDDS_LIB_PATH}/*.a") -install(FILES ${fast_dds_dependencies} DESTINATION lib) - - -file(GLOB libcarla_fastdds_sources - "${libcarla_source_path}/carla/ros2/*.cpp" - "${libcarla_source_path}/carla/ros2/publishers/*.cpp" - "${libcarla_source_path}/carla/ros2/subscribers/*.cpp" - "${libcarla_source_path}/carla/ros2/listeners/*.cpp" - "${libcarla_source_path}/carla/ros2/types/*.cpp") - -# ============================================================================== -# Create targets for debug and release in the same build type. -# ============================================================================== - -if (LIBCARLA_BUILD_RELEASE) - add_library(carla_fastdds STATIC ${libcarla_fastdds_sources}) - - target_compile_options(carla_fastdds PRIVATE -fexceptions) - - target_include_directories(carla_fastdds SYSTEM PRIVATE - "${BOOST_INCLUDE_PATH}" - "${RPCLIB_INCLUDE_PATH}") - - target_include_directories(carla_fastdds PRIVATE "${FASTDDS_INCLUDE_PATH}") - target_include_directories(carla_fastdds PRIVATE "${libcarla_source_path}/carla/ros2") - target_link_libraries(carla_fastdds fastrtps fastcdr "${FAST_DDS_LIBRARIES}") - install(TARGETS carla_fastdds DESTINATION lib) - set_target_properties(carla_fastdds PROPERTIES COMPILE_FLAGS "${CMAKE_CXX_FLAGS_RELEASE}") - -endif() - -if (LIBCARLA_BUILD_DEBUG) - - add_library(carla_fastdds_debug STATIC ${libcarla_fastdds_sources}) - - target_compile_options(carla_fastdds_debug PRIVATE -fexceptions) - - target_include_directories(carla_fastdds_debug SYSTEM PRIVATE - "${BOOST_INCLUDE_PATH}" - "${RPCLIB_INCLUDE_PATH}") - install(TARGETS carla_fastdds_debug DESTINATION lib) - set_target_properties(carla_fastdds_debug PROPERTIES COMPILE_FLAGS "${CMAKE_CXX_FLAGS_DEBUG}") - target_compile_definitions(carla_fastdds_debug PUBLIC -DBOOST_ASIO_ENABLE_BUFFER_DEBUGGING) - -endif() diff --git a/LibCarla/cmake/server/CMakeLists.txt b/LibCarla/cmake/server/CMakeLists.txt index d6e79a5dd85..93cdf287808 100644 --- a/LibCarla/cmake/server/CMakeLists.txt +++ b/LibCarla/cmake/server/CMakeLists.txt @@ -14,66 +14,54 @@ install(FILES ${libcarla_carla_rpclib} DESTINATION lib) install(DIRECTORY "${libcarla_source_path}/compiler" DESTINATION include) -file(GLOB libcarla_carla_headers "${libcarla_source_path}/carla/*.h") -install(FILES ${libcarla_carla_headers} DESTINATION include/carla) - -file(GLOB libcarla_carla_geom_headers "${libcarla_source_path}/carla/geom/*.h") -install(FILES ${libcarla_carla_geom_headers} DESTINATION include/carla/geom) - -file(GLOB libcarla_carla_opendrive "${libcarla_source_path}/carla/opendrive/*.h") -install(FILES ${libcarla_carla_opendrive} DESTINATION include/carla/opendrive) - -file(GLOB libcarla_carla_opendrive_parser "${libcarla_source_path}/carla/opendrive/parser/*.h") -install(FILES ${libcarla_carla_opendrive_parser} DESTINATION include/carla/opendrive/parser) - -file(GLOB libcarla_carla_profiler_headers "${libcarla_source_path}/carla/profiler/*.h") -install(FILES ${libcarla_carla_profiler_headers} DESTINATION include/carla/profiler) - -file(GLOB libcarla_carla_road_headers "${libcarla_source_path}/carla/road/*.h") -install(FILES ${libcarla_carla_road_headers} DESTINATION include/carla/road) - -file(GLOB libcarla_carla_road_element_headers "${libcarla_source_path}/carla/road/element/*.h") -install(FILES ${libcarla_carla_road_element_headers} DESTINATION include/carla/road/element) - -file(GLOB libcarla_carla_road_general_headers "${libcarla_source_path}/carla/road/general/*.h") -install(FILES ${libcarla_carla_road_general_headers} DESTINATION include/carla/road/general) - -file(GLOB libcarla_carla_road_object_headers "${libcarla_source_path}/carla/road/object/*.h") -install(FILES ${libcarla_carla_road_object_headers} DESTINATION include/carla/road/object) - -file(GLOB libcarla_carla_road_signal_headers "${libcarla_source_path}/carla/road/signal/*.h") -install(FILES ${libcarla_carla_road_signal_headers} DESTINATION include/carla/road/signal) - -file(GLOB libcarla_carla_rpc_headers "${libcarla_source_path}/carla/rpc/*.h") -install(FILES ${libcarla_carla_rpc_headers} DESTINATION include/carla/rpc) - -file(GLOB libcarla_carla_sensor_headers "${libcarla_source_path}/carla/sensor/*.h") -install(FILES ${libcarla_carla_sensor_headers} DESTINATION include/carla/sensor) - -file(GLOB libcarla_carla_sensor_data_headers "${libcarla_source_path}/carla/sensor/data/*.h") -install(FILES ${libcarla_carla_sensor_data_headers} DESTINATION include/carla/sensor/data) - -file(GLOB libcarla_carla_sensor_s11n_headers "${libcarla_source_path}/carla/sensor/s11n/*.h") -install(FILES ${libcarla_carla_sensor_s11n_headers} DESTINATION include/carla/sensor/s11n) - -file(GLOB libcarla_carla_streaming_headers "${libcarla_source_path}/carla/streaming/*.h") -install(FILES ${libcarla_carla_streaming_headers} DESTINATION include/carla/streaming) - -file(GLOB libcarla_carla_streaming_detail_headers "${libcarla_source_path}/carla/streaming/detail/*.h") -install(FILES ${libcarla_carla_streaming_detail_headers} DESTINATION include/carla/streaming/detail) - -file(GLOB libcarla_carla_streaming_detail_tcp_headers "${libcarla_source_path}/carla/streaming/detail/tcp/*.h") -install(FILES ${libcarla_carla_streaming_detail_tcp_headers} DESTINATION include/carla/streaming/detail/tcp) - -file(GLOB libcarla_carla_streaming_low_level_headers "${libcarla_source_path}/carla/streaming/low_level/*.h") -install(FILES ${libcarla_carla_streaming_low_level_headers} DESTINATION include/carla/streaming/low_level) - -file(GLOB libcarla_carla_multigpu_headers "${libcarla_source_path}/carla/multigpu/*.h") -install(FILES ${libcarla_carla_multigpu_headers} DESTINATION include/carla/multigpu) - -file(GLOB libcarla_carla_ros2_headers "${libcarla_source_path}/carla/ros2/*.h") -install(FILES ${libcarla_carla_ros2_headers} DESTINATION include/carla/ros2) +foreach(dir "" + "actors/" + "geom/" + "opendrive/" "opendrive/parser/" + "profiler/" + "road/" "road/element/" "road/general/" "road/object/" "road/signal/" + "rpc/" + "sensor/" "sensor/data/" "sensor/s11n/" + "streaming/" "streaming/detail/" "streaming/detail/tcp/" "streaming/low_level/" + "multigpu/") + + file(GLOB headers "${libcarla_source_path}/carla/${dir}*.h") + install(FILES ${headers} DESTINATION include/carla/${dir}) + +endforeach() + +if (LIBCARLA_USE_ROS) + # only install the required public interface headers + foreach(dir "" "types/" ) + file(GLOB libcarla_carla_ros2_public_headers + "${libcarla_source_path}/carla/ros2/${dir}*.h" + ) + install(FILES ${libcarla_carla_ros2_public_headers} DESTINATION include/carla/ros2/${dir}) + endforeach() + + file(GLOB subdirs RELATIVE "${libcarla_source_path}/carla/ros2/fastdds" "${libcarla_source_path}/carla/ros2/fastdds/*") + foreach(typedir "msg" "srv") + foreach(dir ${subdirs}) + if(IS_DIRECTORY "${libcarla_source_path}/carla/ros2/fastdds/${dir}/${typedir}") + file(GLOB libcarla_carla_ros2_types_${dir}_headers + "${libcarla_source_path}/carla/ros2/fastdds/${dir}/${typedir}/*.h" + "${libcarla_source_path}/carla/ros2/fastdds/${dir}/${typedir}/*.hpp" + "${libcarla_source_path}/carla/ros2/fastdds/${dir}/${typedir}/*.ipp" + ) + install(FILES ${libcarla_carla_ros2_types_${dir}_headers} DESTINATION include/carla/ros2/ros_types/${dir}/${typedir}/) + endif() + endforeach() + endforeach() + + file(GLOB fast_dds_dependencies "${FASTDDS_LIB_PATH}/*.a") + install(FILES ${fast_dds_dependencies} DESTINATION lib) + + if(NOT WIN32) + set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -O3" CACHE STRING "" FORCE) + endif() +endif() +# Install boost headers and libraries. install(DIRECTORY "${BOOST_INCLUDE_PATH}/boost" DESTINATION include) if(WIN32) @@ -85,45 +73,62 @@ if(WIN32) endif() # carla_server library. +# carla_server library. +# first the sources which are picked from some directories +set(libcarla_server_sources + "${libcarla_source_path}/carla/Buffer.cpp" + "${libcarla_source_path}/carla/Exception.cpp" + "${libcarla_source_path}/carla/StringUtil.cpp" + # other cpp files only define Deserialize used in client + "${libcarla_source_path}/carla/sensor/s11n/SensorHeaderSerializer.cpp" + ) +# then the globs on the folders to add as a whole +foreach(dir + "actors" + "geom" + "opendrive" "opendrive/parser" + "profiler" + "road" "road/element" "road/general" "road/object" "road/signal" + "rpc" + "sensor" "sensor/data" + "streaming" "streaming/detail" "streaming/detail/tcp" "streaming/low_level" + "multigpu") + + file(GLOB sources "${libcarla_source_path}/carla/${dir}/*.cpp") + list(APPEND libcarla_server_sources ${sources}) + +endforeach() + +foreach(thirdparty_dir + "odrSpiral" + "moodycamel" + "pugixml") + + file(GLOB sources "${libcarla_source_thirdparty_path}/${thirdparty_dir}/*.cpp") + list(APPEND libcarla_server_sources ${sources}) + +endforeach() + +if (LIBCARLA_USE_ROS) + foreach(ros2_dir + "" + "fastdds/carla/ros2/impl/" + "publishers/" + "services/" + "subscribers/" + "types/") + + file(GLOB sources "${libcarla_source_path}/carla/ros2/${ros2_dir}*.cpp") + list(APPEND libcarla_server_sources ${sources}) + endforeach() + + file(GLOB msg_sources "${libcarla_source_path}/carla/ros2/fastdds/*/msg/*.cxx") + list(APPEND libcarla_server_sources ${msg_sources}) + + file(GLOB srv_sources "${libcarla_source_path}/carla/ros2/fastdds/*/srv/*.cxx") + list(APPEND libcarla_server_sources ${srv_sources}) -file(GLOB libcarla_server_sources - "${libcarla_source_path}/carla/*.h" - "${libcarla_source_path}/carla/Buffer.cpp" - "${libcarla_source_path}/carla/Exception.cpp" - "${libcarla_source_path}/carla/geom/*.cpp" - "${libcarla_source_path}/carla/geom/*.h" - "${libcarla_source_path}/carla/opendrive/*.cpp" - "${libcarla_source_path}/carla/opendrive/*.h" - "${libcarla_source_path}/carla/opendrive/parser/*.cpp" - "${libcarla_source_path}/carla/opendrive/parser/*.h" - "${libcarla_source_path}/carla/road/*.cpp" - "${libcarla_source_path}/carla/road/*.h" - "${libcarla_source_path}/carla/road/element/*.cpp" - "${libcarla_source_path}/carla/road/element/*.h" - "${libcarla_source_path}/carla/road/general/*.cpp" - "${libcarla_source_path}/carla/road/general/*.h" - "${libcarla_source_path}/carla/road/object/*.cpp" - "${libcarla_source_path}/carla/road/object/*.h" - "${libcarla_source_path}/carla/road/signal/*.cpp" - "${libcarla_source_path}/carla/road/signal/*.h" - "${libcarla_source_path}/carla/rpc/*.cpp" - "${libcarla_source_path}/carla/rpc/*.h" - "${libcarla_source_path}/carla/sensor/*.h" - "${libcarla_source_path}/carla/sensor/s11n/*.h" - "${libcarla_source_path}/carla/sensor/s11n/SensorHeaderSerializer.cpp" - "${libcarla_source_path}/carla/streaming/*.h" - "${libcarla_source_path}/carla/streaming/detail/*.cpp" - "${libcarla_source_path}/carla/streaming/detail/*.h" - "${libcarla_source_path}/carla/streaming/detail/tcp/*.cpp" - "${libcarla_source_path}/carla/streaming/low_level/*.h" - "${libcarla_source_path}/carla/multigpu/*.h" - "${libcarla_source_path}/carla/multigpu/*.cpp" - "${libcarla_source_thirdparty_path}/odrSpiral/*.cpp" - "${libcarla_source_thirdparty_path}/odrSpiral/*.h" - "${libcarla_source_thirdparty_path}/moodycamel/*.cpp" - "${libcarla_source_thirdparty_path}/moodycamel/*.h" - "${libcarla_source_thirdparty_path}/pugixml/*.cpp" - "${libcarla_source_thirdparty_path}/pugixml/*.hpp") +endif() # ============================================================================== # Create targets for debug and release in the same build type. @@ -141,6 +146,17 @@ if (LIBCARLA_BUILD_RELEASE) set_target_properties(carla_server PROPERTIES COMPILE_FLAGS "${CMAKE_CXX_FLAGS_RELEASE}") + if (LIBCARLA_USE_ROS) + target_include_directories(carla_server SYSTEM PRIVATE + # first the fastdds local folder allowing potential overrides of header files + "${libcarla_source_path}/carla/ros2/fastdds" + "${FASTDDS_INCLUDE_PATH}") + target_link_directories(carla_server PRIVATE ${FASTDDS_LIB_PATH}) + target_link_libraries(carla_server fastrtps fastcdr) + target_compile_definitions(carla_server PUBLIC -DWITH_ROS2) + target_compile_options(carla_server PRIVATE -fexceptions) + endif() + endif() if (LIBCARLA_BUILD_DEBUG) @@ -156,4 +172,15 @@ if (LIBCARLA_BUILD_DEBUG) set_target_properties(carla_server_debug PROPERTIES COMPILE_FLAGS "${CMAKE_CXX_FLAGS_DEBUG}") target_compile_definitions(carla_server_debug PUBLIC -DBOOST_ASIO_ENABLE_BUFFER_DEBUGGING) + if (LIBCARLA_USE_ROS) + target_include_directories(carla_server_debug SYSTEM PRIVATE + # first the fastdds local folder allowing potential overrides of header files + "${libcarla_source_path}/carla/ros2/fastdds" + "${FASTDDS_INCLUDE_PATH}") + target_link_directories(carla_server_debug PRIVATE ${FASTDDS_LIB_PATH}) + target_link_libraries(carla_server_debug fastrtps fastcdr) + target_compile_definitions(carla_server_debug PUBLIC -DWITH_ROS2) + target_compile_options(carla_server_debug PRIVATE -fexceptions) + endif() + endif() diff --git a/LibCarla/cmake/test/CMakeLists.txt b/LibCarla/cmake/test/CMakeLists.txt index 432f509e726..58f7e8cdec1 100644 --- a/LibCarla/cmake/test/CMakeLists.txt +++ b/LibCarla/cmake/test/CMakeLists.txt @@ -15,6 +15,9 @@ endif() link_directories( ${RPCLIB_LIB_PATH} ${GTEST_LIB_PATH}) +if (LIBCARLA_USE_ROS) + link_directories(${FASTDDS_LIB_PATH}) +endif() file(GLOB libcarla_test_sources "${libcarla_source_path}/carla/profiler/*.cpp" diff --git a/LibCarla/source/carla/client/ActorAttribute.cpp b/LibCarla/source/carla/actors/ActorAttribute.cpp similarity index 97% rename from LibCarla/source/carla/client/ActorAttribute.cpp rename to LibCarla/source/carla/actors/ActorAttribute.cpp index 02c27fc2e6e..abf37f6c96e 100644 --- a/LibCarla/source/carla/client/ActorAttribute.cpp +++ b/LibCarla/source/carla/actors/ActorAttribute.cpp @@ -4,14 +4,14 @@ // This work is licensed under the terms of the MIT license. // For a copy, see . -#include "carla/client/ActorAttribute.h" +#include "carla/actors/ActorAttribute.h" #include "carla/Exception.h" #include "carla/Logging.h" #include "carla/StringUtil.h" namespace carla { -namespace client { +namespace actors { #define LIBCARLA_THROW_INVALID_VALUE(message) throw_exception(InvalidAttributeValue(GetId() + ": " + message)); #define LIBCARLA_THROW_BAD_VALUE_CAST(type) \ @@ -103,5 +103,5 @@ namespace client { #undef LIBCARLA_THROW_BAD_VALUE_CAST #undef LIBCARLA_THROW_INVALID_VALUE -} // namespace client +} // namespace actors } // namespace carla diff --git a/LibCarla/source/carla/client/ActorAttribute.h b/LibCarla/source/carla/actors/ActorAttribute.h similarity index 99% rename from LibCarla/source/carla/client/ActorAttribute.h rename to LibCarla/source/carla/actors/ActorAttribute.h index 5585f1cc9e6..78fbe854482 100644 --- a/LibCarla/source/carla/client/ActorAttribute.h +++ b/LibCarla/source/carla/actors/ActorAttribute.h @@ -14,7 +14,7 @@ #include namespace carla { -namespace client { +namespace actors { // =========================================================================== // -- InvalidAttributeValue -------------------------------------------------- @@ -237,5 +237,5 @@ namespace client { return rhs.operator==(*this); } -} // namespace client +} // namespace actors } // namespace carla diff --git a/LibCarla/source/carla/client/ActorBlueprint.cpp b/LibCarla/source/carla/actors/ActorBlueprint.cpp similarity index 95% rename from LibCarla/source/carla/client/ActorBlueprint.cpp rename to LibCarla/source/carla/actors/ActorBlueprint.cpp index 12895664cf3..1c4a83972d6 100644 --- a/LibCarla/source/carla/client/ActorBlueprint.cpp +++ b/LibCarla/source/carla/actors/ActorBlueprint.cpp @@ -4,7 +4,7 @@ // This work is licensed under the terms of the MIT license. // For a copy, see . -#include "carla/client/ActorBlueprint.h" +#include "carla/actors/ActorBlueprint.h" #include "carla/Exception.h" #include "carla/StringUtil.h" @@ -12,7 +12,7 @@ #include namespace carla { -namespace client { +namespace actors { template static void FillMap(Map &destination, Container &source) { @@ -62,5 +62,5 @@ namespace client { return description; } -} // namespace client +} // namespace actors } // namespace carla diff --git a/LibCarla/source/carla/client/ActorBlueprint.h b/LibCarla/source/carla/actors/ActorBlueprint.h similarity index 97% rename from LibCarla/source/carla/client/ActorBlueprint.h rename to LibCarla/source/carla/actors/ActorBlueprint.h index f08b7d09d86..06fc306d868 100644 --- a/LibCarla/source/carla/client/ActorBlueprint.h +++ b/LibCarla/source/carla/actors/ActorBlueprint.h @@ -8,7 +8,7 @@ #include "carla/Debug.h" #include "carla/Iterator.h" -#include "carla/client/ActorAttribute.h" +#include "carla/actors/ActorAttribute.h" #include "carla/rpc/ActorDefinition.h" #include "carla/rpc/ActorDescription.h" @@ -17,7 +17,7 @@ #include namespace carla { -namespace client { +namespace actors { /// Contains all the necessary information for spawning an Actor. class ActorBlueprint { @@ -120,5 +120,5 @@ namespace client { std::unordered_map _attributes; }; -} // namespace client +} // namespace actors } // namespace carla diff --git a/LibCarla/source/carla/client/BlueprintLibrary.cpp b/LibCarla/source/carla/actors/BlueprintLibrary.cpp similarity index 96% rename from LibCarla/source/carla/client/BlueprintLibrary.cpp rename to LibCarla/source/carla/actors/BlueprintLibrary.cpp index 81e4ada9481..afda8308ee3 100644 --- a/LibCarla/source/carla/client/BlueprintLibrary.cpp +++ b/LibCarla/source/carla/actors/BlueprintLibrary.cpp @@ -4,7 +4,7 @@ // This work is licensed under the terms of the MIT license. // For a copy, see . -#include "carla/client/BlueprintLibrary.h" +#include "carla/actors/BlueprintLibrary.h" #include "carla/Exception.h" @@ -12,7 +12,7 @@ #include namespace carla { -namespace client { +namespace actors { BlueprintLibrary::BlueprintLibrary( const std::vector &blueprints) { @@ -85,5 +85,5 @@ namespace client { return operator[](pos); } -} // namespace client +} // namespace actors } // namespace carla diff --git a/LibCarla/source/carla/client/BlueprintLibrary.h b/LibCarla/source/carla/actors/BlueprintLibrary.h similarity index 97% rename from LibCarla/source/carla/client/BlueprintLibrary.h rename to LibCarla/source/carla/actors/BlueprintLibrary.h index 03986c07603..7a6677b4ef6 100644 --- a/LibCarla/source/carla/client/BlueprintLibrary.h +++ b/LibCarla/source/carla/actors/BlueprintLibrary.h @@ -10,14 +10,14 @@ #include "carla/Iterator.h" #include "carla/Memory.h" #include "carla/NonCopyable.h" -#include "carla/client/ActorBlueprint.h" +#include "carla/actors/ActorBlueprint.h" #include #include #include namespace carla { -namespace client { +namespace actors { /// @todo Works as a list but its actually a map. We should assess the use /// cases and reconsider this implementation. @@ -84,5 +84,5 @@ namespace client { map_type _blueprints; }; -} // namespace client +} // namespace actors } // namespace carla diff --git a/LibCarla/source/carla/client/Actor.cpp b/LibCarla/source/carla/client/Actor.cpp index dd3ede948ac..b06bd7a77fe 100644 --- a/LibCarla/source/carla/client/Actor.cpp +++ b/LibCarla/source/carla/client/Actor.cpp @@ -20,15 +20,15 @@ namespace client { return GetEpisode().Lock()->GetActorTransform(*this); } - geom::Vector3D Actor::GetVelocity() const { + geom::Velocity Actor::GetVelocity() const { return GetEpisode().Lock()->GetActorVelocity(*this); } - geom::Vector3D Actor::GetAngularVelocity() const { + geom::AngularVelocity Actor::GetAngularVelocity() const { return GetEpisode().Lock()->GetActorAngularVelocity(*this); } - geom::Vector3D Actor::GetAcceleration() const { + geom::Acceleration Actor::GetAcceleration() const { return GetEpisode().Lock()->GetActorAcceleration(*this); } @@ -146,6 +146,18 @@ namespace client { return GetEpisode().Lock()->GetActorState(*this); } + void Actor::EnableForROS() { + GetEpisode().Lock()->EnableForROS(*this); + } + + void Actor::DisableForROS() { + GetEpisode().Lock()->DisableForROS(*this); + } + + bool Actor::IsEnabledForROS(){ + return GetEpisode().Lock()->IsEnabledForROS(*this); + } + bool Actor::Destroy() { rpc::ActorState actor_state = GetActorState(); bool result = false; diff --git a/LibCarla/source/carla/client/Actor.h b/LibCarla/source/carla/client/Actor.h index fb6f1b7b8da..373ed3ebf76 100644 --- a/LibCarla/source/carla/client/Actor.h +++ b/LibCarla/source/carla/client/Actor.h @@ -9,6 +9,9 @@ #include "carla/Debug.h" #include "carla/Memory.h" #include "carla/client/detail/ActorState.h" +#include "carla/geom/Acceleration.h" +#include "carla/geom/AngularVelocity.h" +#include "carla/geom/Velocity.h" #include "carla/profiler/LifetimeProfiled.h" namespace carla { @@ -45,19 +48,19 @@ namespace client { /// /// @note This function does not call the simulator, it returns the /// velocity received in the last tick. - geom::Vector3D GetVelocity() const; + geom::Velocity GetVelocity() const; /// Return the current 3D angular velocity of the actor. /// /// @note This function does not call the simulator, it returns the /// angular velocity received in the last tick. - geom::Vector3D GetAngularVelocity() const; + geom::AngularVelocity GetAngularVelocity() const; /// Return the current 3D acceleration of the actor. /// /// @note This function does not call the simulator, it returns the /// acceleration calculated after the actor's velocity. - geom::Vector3D GetAcceleration() const; + geom::Acceleration GetAcceleration() const; geom::BoundingBox GetBoundingBox() const; @@ -141,6 +144,15 @@ namespace client { return GetEpisode().IsValid() && GetActorState() == rpc::ActorState::Active; } + /// Enable this actor for ROS2 publishing + void EnableForROS(); + + /// Disable this actor for ROS2 publishing + void DisableForROS(); + + /// Return if the actor is publishing for ROS2 + bool IsEnabledForROS(); + /// Tell the simulator to destroy this Actor, and return whether the actor /// was successfully destroyed. /// diff --git a/LibCarla/source/carla/client/ServerSideSensor.cpp b/LibCarla/source/carla/client/ServerSideSensor.cpp index f186d63a0f4..c9135fb52cd 100644 --- a/LibCarla/source/carla/client/ServerSideSensor.cpp +++ b/LibCarla/source/carla/client/ServerSideSensor.cpp @@ -55,14 +55,14 @@ namespace client { listening_mask.reset(0); } - void ServerSideSensor::Send(std::string message) { + void ServerSideSensor::Send(const rpc::CustomV2XBytes &data) { log_debug("calling sensor Send() ", GetDisplayId()); if (GetActorDescription().description.id != "sensor.other.v2x_custom") { log_warning("Send methods are not supported on non-V2x sensors (sensor.other.v2x_custom)."); return; } - GetEpisode().Lock()->Send(*this,message); + GetEpisode().Lock()->Send(*this,data); } void ServerSideSensor::EnableGBuffers(bool bEnabled) { @@ -94,18 +94,6 @@ namespace client { listening_mask.reset(GBufferId + 1); } - void ServerSideSensor::EnableForROS() { - GetEpisode().Lock()->EnableForROS(*this); - } - - void ServerSideSensor::DisableForROS() { - GetEpisode().Lock()->DisableForROS(*this); - } - - bool ServerSideSensor::IsEnabledForROS(){ - return GetEpisode().Lock()->IsEnabledForROS(*this); - } - bool ServerSideSensor::Destroy() { log_debug("calling sensor Destroy() ", GetDisplayId()); if (IsListening()) { diff --git a/LibCarla/source/carla/client/ServerSideSensor.h b/LibCarla/source/carla/client/ServerSideSensor.h index 006afb65f33..378a567d2e2 100644 --- a/LibCarla/source/carla/client/ServerSideSensor.h +++ b/LibCarla/source/carla/client/ServerSideSensor.h @@ -6,9 +6,11 @@ #pragma once -#include "carla/client/Sensor.h" #include +#include "carla/client/Sensor.h" +#include "carla/rpc/CustomV2XBytes.h" + namespace carla { namespace client { @@ -50,17 +52,8 @@ namespace client { return listening_mask.test(id + 1); } - /// Enable this sensor for ROS2 publishing - void EnableForROS(); - - /// Disable this sensor for ROS2 publishing - void DisableForROS(); - - /// Return if the sensor is publishing for ROS2 - bool IsEnabledForROS(); - /// Send data via this sensor - void Send(std::string message); + void Send(const rpc::CustomV2XBytes &data); /// @copydoc Actor::Destroy() /// diff --git a/LibCarla/source/carla/client/Vehicle.cpp b/LibCarla/source/carla/client/Vehicle.cpp index 9dcf3f194ac..6baaa5c3aea 100644 --- a/LibCarla/source/carla/client/Vehicle.cpp +++ b/LibCarla/source/carla/client/Vehicle.cpp @@ -104,7 +104,11 @@ namespace client { } Vehicle::Control Vehicle::GetControl() const { - return GetEpisode().Lock()->GetActorSnapshot(*this).state.vehicle_data.control; + return GetEpisode().Lock()->GetActorSnapshot(*this).state.vehicle_data.GetVehicleControl(); + } + + Vehicle::AckermannControl Vehicle::GetAckermannControl() const { + return GetEpisode().Lock()->GetActorSnapshot(*this).state.vehicle_data.GetAckermannControl(); } Vehicle::PhysicsControl Vehicle::GetPhysicsControl() const { diff --git a/LibCarla/source/carla/client/Vehicle.h b/LibCarla/source/carla/client/Vehicle.h index 8f5a38797f4..cd51f7289a5 100644 --- a/LibCarla/source/carla/client/Vehicle.h +++ b/LibCarla/source/carla/client/Vehicle.h @@ -102,8 +102,16 @@ namespace client { /// /// @note This function does not call the simulator, it returns the data /// received in the last tick. + /// @note This function only returns valid data if the ackermann control is inactive. Control GetControl() const; + /// Return the ackermann control last applied to this vehicle. + /// + /// @note This function does not call the simulator, it returns the data + /// received in the last tick. + /// @note This function only returns valid data if the vehicle control is inactive. + AckermannControl GetAckermannControl() const; + /// Return the physics control last applied to this vehicle. /// /// @warning This function does call the simulator. diff --git a/LibCarla/source/carla/client/World.cpp b/LibCarla/source/carla/client/World.cpp index 79b5540701d..5b2f8d69917 100644 --- a/LibCarla/source/carla/client/World.cpp +++ b/LibCarla/source/carla/client/World.cpp @@ -8,7 +8,7 @@ #include "carla/Logging.h" #include "carla/client/Actor.h" -#include "carla/client/ActorBlueprint.h" +#include "carla/actors/ActorBlueprint.h" #include "carla/client/ActorList.h" #include "carla/client/detail/Simulator.h" #include "carla/StringUtil.h" @@ -33,7 +33,7 @@ namespace client { _episode.Lock()->UnloadLevelLayer(map_layers); } - SharedPtr World::GetBlueprintLibrary() const { + SharedPtr World::GetBlueprintLibrary() const { return _episode.Lock()->GetBlueprintLibrary(); } @@ -125,7 +125,7 @@ namespace client { } SharedPtr World::SpawnActor( - const ActorBlueprint &blueprint, + const actors::ActorBlueprint &blueprint, const geom::Transform &transform, Actor *parent_actor, rpc::AttachmentType attachment_type, @@ -134,7 +134,7 @@ namespace client { } SharedPtr World::TrySpawnActor( - const ActorBlueprint &blueprint, + const actors::ActorBlueprint &blueprint, const geom::Transform &transform, Actor *parent_actor, rpc::AttachmentType attachment_type, diff --git a/LibCarla/source/carla/client/World.h b/LibCarla/source/carla/client/World.h index 460f1f71aea..07993713ea8 100644 --- a/LibCarla/source/carla/client/World.h +++ b/LibCarla/source/carla/client/World.h @@ -33,12 +33,16 @@ #include namespace carla { + +namespace actors { + class ActorBlueprint; + class BlueprintLibrary; +} + namespace client { class Actor; - class ActorBlueprint; class ActorList; - class BlueprintLibrary; class Map; class TrafficLight; class TrafficSign; @@ -70,7 +74,7 @@ namespace client { /// Return the list of blueprints available in this world. This blueprints /// can be used to spawning actor into the world. - SharedPtr GetBlueprintLibrary() const; + SharedPtr GetBlueprintLibrary() const; /// Returns a list of pairs where the firts element is the vehicle ID /// and the second one is the light state @@ -116,7 +120,7 @@ namespace client { /// transform. If a @a parent is provided, the actor is attached to /// @a parent. SharedPtr SpawnActor( - const ActorBlueprint &blueprint, + const actors::ActorBlueprint &blueprint, const geom::Transform &transform, Actor *parent = nullptr, rpc::AttachmentType attachment_type = rpc::AttachmentType::Rigid, @@ -125,7 +129,7 @@ namespace client { /// Same as SpawnActor but return nullptr on failure instead of throwing an /// exception. SharedPtr TrySpawnActor( - const ActorBlueprint &blueprint, + const actors::ActorBlueprint &blueprint, const geom::Transform &transform, Actor *parent = nullptr, rpc::AttachmentType attachment_type = rpc::AttachmentType::Rigid, diff --git a/LibCarla/source/carla/client/detail/ActorState.h b/LibCarla/source/carla/client/detail/ActorState.h index 503048fa229..dfa57517ca3 100644 --- a/LibCarla/source/carla/client/detail/ActorState.h +++ b/LibCarla/source/carla/client/detail/ActorState.h @@ -8,7 +8,7 @@ #include "carla/NonCopyable.h" #include "carla/client/World.h" -#include "carla/client/ActorAttribute.h" +#include "carla/actors/ActorAttribute.h" #include "carla/client/detail/EpisodeProxy.h" #include "carla/rpc/Actor.h" @@ -48,7 +48,7 @@ namespace detail { return World{_episode}; } - const std::vector &GetAttributes() const + const std::vector &GetAttributes() const { return _attributes; } @@ -83,7 +83,7 @@ namespace detail { std::string _display_id; - std::vector _attributes; + std::vector _attributes; }; } // namespace detail diff --git a/LibCarla/source/carla/client/detail/Client.cpp b/LibCarla/source/carla/client/detail/Client.cpp index a632e69804f..294b314de69 100644 --- a/LibCarla/source/carla/client/detail/Client.cpp +++ b/LibCarla/source/carla/client/detail/Client.cpp @@ -381,7 +381,7 @@ namespace detail { if (attachment_type == rpc::AttachmentType::SpringArm || attachment_type == rpc::AttachmentType::SpringArmGhost) { - const auto a = transform.location.MakeSafeUnitVector(std::numeric_limits::epsilon()); + const auto a = transform.location.MakeUnitVector(std::numeric_limits::epsilon()); const auto z = geom::Vector3D(0.0f, 0.f, 1.0f); constexpr float OneEps = 1.0f - std::numeric_limits::epsilon(); if (geom::Math::Dot(a, z) > OneEps) { @@ -712,23 +712,20 @@ namespace detail { _pimpl->streaming_client.UnSubscribe(token); } - void Client::EnableForROS(const streaming::Token &token) { - carla::streaming::detail::token_type thisToken(token); - _pimpl->AsyncCall("enable_sensor_for_ros", thisToken.get_stream_id()); + void Client::EnableForROS(const rpc::ActorId actor) { + _pimpl->AsyncCall("enable_actor_for_ros", actor); } - void Client::DisableForROS(const streaming::Token &token) { - carla::streaming::detail::token_type thisToken(token); - _pimpl->AsyncCall("disable_sensor_for_ros", thisToken.get_stream_id()); + void Client::DisableForROS(const rpc::ActorId actor) { + _pimpl->AsyncCall("disable_actor_for_ros", actor); } - bool Client::IsEnabledForROS(const streaming::Token &token) { - carla::streaming::detail::token_type thisToken(token); - return _pimpl->CallAndWait("is_sensor_enabled_for_ros", thisToken.get_stream_id()); + bool Client::IsEnabledForROS(const rpc::ActorId actor) { + return _pimpl->CallAndWait("is_actor_enabled_for_ros", actor); } - void Client::Send(rpc::ActorId ActorId, std::string message) { - _pimpl->AsyncCall("send", ActorId, message); + void Client::Send(rpc::ActorId ActorId, const rpc::CustomV2XBytes &data) { + _pimpl->AsyncCall("send", ActorId, data); } void Client::SetIgnoredVehicles(rpc::ActorId ActorId, const std::vector& vehicle_ids) { diff --git a/LibCarla/source/carla/client/detail/Client.h b/LibCarla/source/carla/client/detail/Client.h index 1ed21680a7f..e1294d78a32 100644 --- a/LibCarla/source/carla/client/detail/Client.h +++ b/LibCarla/source/carla/client/detail/Client.h @@ -16,6 +16,7 @@ #include "carla/rpc/AttachmentType.h" #include "carla/rpc/Command.h" #include "carla/rpc/CommandResponse.h" +#include "carla/rpc/CustomV2XBytes.h" #include "carla/rpc/EnvironmentObject.h" #include "carla/rpc/EpisodeInfo.h" #include "carla/rpc/EpisodeSettings.h" @@ -457,17 +458,17 @@ namespace detail { void UnSubscribeFromStream(const streaming::Token &token); - void EnableForROS(const streaming::Token &token); + void EnableForROS(const rpc::ActorId actor); - void DisableForROS(const streaming::Token &token); + void DisableForROS(const rpc::ActorId actor); - bool IsEnabledForROS(const streaming::Token &token); + bool IsEnabledForROS(const rpc::ActorId actor); void UnSubscribeFromGBuffer( rpc::ActorId ActorId, uint32_t GBufferId); - void Send(rpc::ActorId ActorId, std::string message); + void Send(rpc::ActorId ActorId, const rpc::CustomV2XBytes &data); void SetIgnoredVehicles(rpc::ActorId ActorId, const std::vector& vehicle_ids); diff --git a/LibCarla/source/carla/client/detail/Episode.cpp b/LibCarla/source/carla/client/detail/Episode.cpp index d706ccaf28f..e7ab247ca9c 100644 --- a/LibCarla/source/carla/client/detail/Episode.cpp +++ b/LibCarla/source/carla/client/detail/Episode.cpp @@ -38,10 +38,10 @@ using namespace std::chrono_literals; : Episode(client, client.GetEpisodeInfo(), simulator) {} Episode::Episode(Client &client, const rpc::EpisodeInfo &info, std::weak_ptr simulator) - : _client(client), - _state(std::make_shared(info.id)), - _simulator(simulator), - _token(info.token) {} + : _client(client) + , _state(std::make_shared(info.id)) + , _token(info.token) + , _simulator(simulator) {} Episode::~Episode() { try { @@ -57,7 +57,7 @@ using namespace std::chrono_literals; auto self = weak.lock(); if (self != nullptr) { - auto data = sensor::Deserializer::Deserialize(std::move(buffer)); + auto data = sensor::Deserializer::Deserialize(DESERIALIZE_MOVE_DATA(buffer)); auto next = std::make_shared(CastData(*data)); auto prev = self->GetState(); diff --git a/LibCarla/source/carla/client/detail/Simulator.cpp b/LibCarla/source/carla/client/detail/Simulator.cpp index 6ad47e3fe06..71533c0e126 100644 --- a/LibCarla/source/carla/client/detail/Simulator.cpp +++ b/LibCarla/source/carla/client/detail/Simulator.cpp @@ -10,7 +10,7 @@ #include "carla/Exception.h" #include "carla/Logging.h" #include "carla/RecurrentSharedFuture.h" -#include "carla/client/BlueprintLibrary.h" +#include "carla/actors/BlueprintLibrary.h" #include "carla/client/FileTransfer.h" #include "carla/client/Map.h" #include "carla/client/Sensor.h" @@ -246,9 +246,9 @@ EpisodeProxy Simulator::GetCurrentEpisode() { // -- Access to global objects in the episode -------------------------------- // =========================================================================== - SharedPtr Simulator::GetBlueprintLibrary() { + SharedPtr Simulator::GetBlueprintLibrary() { auto defs = _client.GetActorDefinitions(); - return MakeShared(std::move(defs)); + return MakeShared(std::move(defs)); } rpc::VehicleLightStateList Simulator::GetVehiclesLightStates() { @@ -350,7 +350,7 @@ EpisodeProxy Simulator::GetCurrentEpisode() { // =========================================================================== SharedPtr Simulator::SpawnActor( - const ActorBlueprint &blueprint, + const actors::ActorBlueprint &blueprint, const geom::Transform &transform, Actor *parent, rpc::AttachmentType attachment_type, @@ -394,6 +394,19 @@ EpisodeProxy Simulator::GetCurrentEpisode() { return success; } + void Simulator::EnableForROS(const Actor &actor) { + _client.EnableForROS(actor.GetId()); + } + + void Simulator::DisableForROS(const Actor &actor) { + _client.DisableForROS(actor.GetId()); + } + + bool Simulator::IsEnabledForROS(const Actor &actor) { + return _client.IsEnabledForROS(actor.GetId()); + } + + // =========================================================================== // -- Operations with sensors ------------------------------------------------ // =========================================================================== @@ -409,7 +422,7 @@ EpisodeProxy Simulator::GetCurrentEpisode() { _client.SubscribeToStream( sensor.GetActorDescription().GetStreamToken(), [cb=std::move(callback), ep=WeakEpisodeProxy{shared_from_this()}](auto buffer) { - auto data = sensor::Deserializer::Deserialize(std::move(buffer)); + auto data = sensor::Deserializer::Deserialize(DESERIALIZE_MOVE_DATA(buffer)); data->_episode = ep.TryLock(); cb(std::move(data)); }); @@ -420,25 +433,13 @@ EpisodeProxy Simulator::GetCurrentEpisode() { // If in the future we need to unsubscribe from each gbuffer individually, it should be done here. } - void Simulator::EnableForROS(const Sensor &sensor) { - _client.EnableForROS(sensor.GetActorDescription().GetStreamToken()); - } - - void Simulator::DisableForROS(const Sensor &sensor) { - _client.DisableForROS(sensor.GetActorDescription().GetStreamToken()); - } - - bool Simulator::IsEnabledForROS(const Sensor &sensor) { - return _client.IsEnabledForROS(sensor.GetActorDescription().GetStreamToken()); - } - void Simulator::SubscribeToGBuffer( Actor &actor, uint32_t gbuffer_id, std::function)> callback) { _client.SubscribeToGBuffer(actor.GetId(), gbuffer_id, [cb=std::move(callback), ep=WeakEpisodeProxy{shared_from_this()}](auto buffer) { - auto data = sensor::Deserializer::Deserialize(std::move(buffer)); + auto data = sensor::Deserializer::Deserialize(DESERIALIZE_MOVE_DATA(buffer)); data->_episode = ep.TryLock(); cb(std::move(data)); }); @@ -452,8 +453,8 @@ EpisodeProxy Simulator::GetCurrentEpisode() { _client.FreezeAllTrafficLights(frozen); } - void Simulator::Send(const Sensor &sensor, std::string message) { - _client.Send(sensor.GetId(), message); + void Simulator::Send(const Sensor &sensor, const carla::rpc::CustomV2XBytes &data) { + _client.Send(sensor.GetId(), data); } void Simulator::SetIgnoredVehicles(const Sensor &sensor, const std::vector& vehicle_ids) { diff --git a/LibCarla/source/carla/client/detail/Simulator.h b/LibCarla/source/carla/client/detail/Simulator.h index 72d5b9a7b20..89c0ba3fc6b 100644 --- a/LibCarla/source/carla/client/detail/Simulator.h +++ b/LibCarla/source/carla/client/detail/Simulator.h @@ -22,6 +22,7 @@ #include "carla/client/detail/Episode.h" #include "carla/client/detail/EpisodeProxy.h" #include "carla/profiler/LifetimeProfiled.h" +#include "carla/rpc/CustomV2XBytes.h" #include "carla/rpc/TrafficLightState.h" #include "carla/rpc/VehicleLightStateList.h" #include "carla/rpc/LabelledPoint.h" @@ -34,10 +35,14 @@ #include namespace carla { -namespace client { +namespace actors { class ActorBlueprint; class BlueprintLibrary; +} + +namespace client { + class Map; class Sensor; class WalkerAIController; @@ -237,7 +242,7 @@ namespace detail { _episode->AddPendingException(e); } - SharedPtr GetBlueprintLibrary(); + SharedPtr GetBlueprintLibrary(); /// Returns a list of pairs where the firts element is the vehicle ID /// and the second one is the light state @@ -366,7 +371,7 @@ namespace detail { /// actor. If @gc is GarbageCollectionPolicy::Inherit, the default garbage /// collection policy is used. SharedPtr SpawnActor( - const ActorBlueprint &blueprint, + const actors::ActorBlueprint &blueprint, const geom::Transform &transform, Actor *parent = nullptr, rpc::AttachmentType attachment_type = rpc::AttachmentType::Rigid, @@ -380,6 +385,12 @@ namespace detail { return _client.DestroyActor(actor_id); } + void EnableForROS(const Actor &actor); + + void DisableForROS(const Actor &actor); + + bool IsEnabledForROS(const Actor &actor); + ActorSnapshot GetActorSnapshot(ActorId actor_id) const { DEBUG_ASSERT(_episode != nullptr); return _episode->GetState()->GetActorSnapshot(actor_id); @@ -710,15 +721,8 @@ namespace detail { std::function)> callback); void UnSubscribeFromSensor(Actor &sensor); - void EnableGBuffers(const Sensor &sensor, bool bEnable); - void DisableForROS(const Sensor &sensor); - - bool IsEnabledForROS(const Sensor &sensor); - - void EnableForROS(const Sensor &sensor); - void SubscribeToGBuffer( Actor & sensor, uint32_t gbuffer_id, @@ -728,7 +732,7 @@ namespace detail { Actor & sensor, uint32_t gbuffer_id); - void Send(const Sensor &sensor, std::string message); + void Send(const Sensor &sensor, const rpc::CustomV2XBytes &data); void SetIgnoredVehicles(const Sensor &sensor, const std::vector& vehicle_ids); diff --git a/LibCarla/source/carla/geom/Acceleration.h b/LibCarla/source/carla/geom/Acceleration.h new file mode 100644 index 00000000000..e470f824062 --- /dev/null +++ b/LibCarla/source/carla/geom/Acceleration.h @@ -0,0 +1,98 @@ +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/geom/Vector3D.h" +#include "carla/geom/Vector3DInt.h" +#include "carla/geom/Math.h" + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 +#include +#include "Math/Vector.h" +#include +#endif // LIBCARLA_INCLUDED_FROM_UE4 + +namespace carla { +namespace geom { + + /** + * Stores the acceleration vector of an entity in m/s² + */ + class Acceleration : public Vector3D { + public: + + // ========================================================================= + // -- Constructors --------------------------------------------------------- + // ========================================================================= + + Acceleration() = default; + + using Vector3D::Vector3D; + + Acceleration(const Vector3D &rhs) : Vector3D(rhs) {} + + Acceleration(const Vector3DInt &rhs) : + Vector3D(static_cast(rhs.x), + static_cast(rhs.y), + static_cast(rhs.z)) {} + + // ========================================================================= + // -- Arithmetic operators ------------------------------------------------- + // ========================================================================= + + Acceleration &operator+=(const Acceleration &rhs) { + static_cast(*this) += static_cast(rhs); + return *this; + } + + friend Acceleration operator+(Acceleration lhs, const Acceleration &rhs) { + lhs += rhs; + return lhs; + } + + Acceleration &operator-=(const Acceleration &rhs) { + static_cast(*this) -= static_cast(rhs); + return *this; + } + + friend Acceleration operator-(Acceleration lhs, const Acceleration &rhs) { + lhs -= rhs; + return lhs; + } + + // ========================================================================= + // -- Comparison operators ------------------------------------------------- + // ========================================================================= + + bool operator==(const Acceleration &rhs) const { + return static_cast(*this) == static_cast(rhs); + } + + bool operator!=(const Acceleration &rhs) const { + return !(*this == rhs); + } + + // ========================================================================= + // -- Conversions to UE4 types --------------------------------------------- + // ========================================================================= + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + // from cm/s² to m/s². + Acceleration(const FVector &vector) + : Acceleration(1e-2f * vector.X, 1e-2f * vector.Y, 1e-2f * vector.Z) {} + + // from m/s² to cm/s² + operator FVector() const { + return FVector{1e2f * x, 1e2f * y, 1e2f * z}; + } + +#endif // LIBCARLA_INCLUDED_FROM_UE4 + }; + +} // namespace geom +} // namespace carla diff --git a/LibCarla/source/carla/geom/AngularVelocity.h b/LibCarla/source/carla/geom/AngularVelocity.h new file mode 100644 index 00000000000..767b7959cde --- /dev/null +++ b/LibCarla/source/carla/geom/AngularVelocity.h @@ -0,0 +1,98 @@ +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/geom/Vector3D.h" +#include "carla/geom/Vector3DInt.h" +#include "carla/geom/Math.h" + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 +#include +#include "Math/Vector.h" +#include +#endif // LIBCARLA_INCLUDED_FROM_UE4 + +namespace carla { +namespace geom { + + /** + * Stores the angular velocity vector in deg/s + */ + class AngularVelocity : public Vector3D { + public: + + // ========================================================================= + // -- Constructors --------------------------------------------------------- + // ========================================================================= + + AngularVelocity() = default; + + using Vector3D::Vector3D; + + AngularVelocity(const Vector3D &rhs) : Vector3D(rhs) {} + + AngularVelocity(const Vector3DInt &rhs) : + Vector3D(static_cast(rhs.x), + static_cast(rhs.y), + static_cast(rhs.z)) {} + + // ========================================================================= + // -- Arithmetic operators ------------------------------------------------- + // ========================================================================= + + AngularVelocity &operator+=(const AngularVelocity &rhs) { + static_cast(*this) += static_cast(rhs); + return *this; + } + + friend AngularVelocity operator+(AngularVelocity lhs, const AngularVelocity &rhs) { + lhs += rhs; + return lhs; + } + + AngularVelocity &operator-=(const AngularVelocity &rhs) { + static_cast(*this) -= static_cast(rhs); + return *this; + } + + friend AngularVelocity operator-(AngularVelocity lhs, const AngularVelocity &rhs) { + lhs -= rhs; + return lhs; + } + + // ========================================================================= + // -- Comparison operators ------------------------------------------------- + // ========================================================================= + + bool operator==(const AngularVelocity &rhs) const { + return static_cast(*this) == static_cast(rhs); + } + + bool operator!=(const AngularVelocity &rhs) const { + return !(*this == rhs); + } + + // ========================================================================= + // -- Conversions to UE4 types --------------------------------------------- + // ========================================================================= + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + // in future potentially transform deg/s -> rad/s? + AngularVelocity(const FVector &vector) + : Vector3D(vector.X, vector.Y, vector.Z) {} + + // in future potentially transform rad/s -> deg/s? + operator FVector() const { + return FVector{x, y, z}; + } + +#endif // LIBCARLA_INCLUDED_FROM_UE4 + }; + +} // namespace geom +} // namespace carla diff --git a/LibCarla/source/carla/geom/BoundingBox.h b/LibCarla/source/carla/geom/BoundingBox.h index af4c10b828d..e2d0a06183d 100644 --- a/LibCarla/source/carla/geom/BoundingBox.h +++ b/LibCarla/source/carla/geom/BoundingBox.h @@ -83,14 +83,14 @@ namespace geom { std::array GetLocalVertices() const { return {{ - location + Location(rotation.RotateVector({-extent.x,-extent.y,-extent.z})), - location + Location(rotation.RotateVector({-extent.x,-extent.y, extent.z})), - location + Location(rotation.RotateVector({-extent.x, extent.y,-extent.z})), - location + Location(rotation.RotateVector({-extent.x, extent.y, extent.z})), - location + Location(rotation.RotateVector({ extent.x,-extent.y,-extent.z})), - location + Location(rotation.RotateVector({ extent.x,-extent.y, extent.z})), - location + Location(rotation.RotateVector({ extent.x, extent.y,-extent.z})), - location + Location(rotation.RotateVector({ extent.x, extent.y, extent.z})) + location + Location(rotation.RotatedVector(Location(-extent.x,-extent.y,-extent.z))), + location + Location(rotation.RotatedVector(Location(-extent.x,-extent.y, extent.z))), + location + Location(rotation.RotatedVector(Location(-extent.x, extent.y,-extent.z))), + location + Location(rotation.RotatedVector(Location(-extent.x, extent.y, extent.z))), + location + Location(rotation.RotatedVector(Location( extent.x,-extent.y,-extent.z))), + location + Location(rotation.RotatedVector(Location( extent.x,-extent.y, extent.z))), + location + Location(rotation.RotatedVector(Location( extent.x, extent.y,-extent.z))), + location + Location(rotation.RotatedVector(Location( extent.x, extent.y, extent.z))) }}; } diff --git a/LibCarla/source/carla/geom/Math.cpp b/LibCarla/source/carla/geom/Math.cpp index a3a6a9d54ad..3856f05dfba 100644 --- a/LibCarla/source/carla/geom/Math.cpp +++ b/LibCarla/source/carla/geom/Math.cpp @@ -7,12 +7,38 @@ #include "carla/geom/Math.h" #include "carla/geom/Rotation.h" +#include "carla/geom/Quaternion.h" namespace carla { namespace geom { - double Math::GetVectorAngle(const Vector3D &a, const Vector3D &b) { - return std::acos(Dot(a, b) / (a.Length() * b.Length())); + float Math::SineVectorAngleFromUnitVectors(Vector3D const &a_unit, Vector3D const &b_unit) + { + auto const cross = Math::Cross(a_unit, b_unit); + Vector3D const to_up(0.f, 0.f, 1.f); + auto const sine_angle_abs = Math::Length(cross); + if ( std::signbit(Math::Dot(cross, to_up) ) ) + { + return -sine_angle_abs; + } + else + { + return sine_angle_abs; + } + } + + float Math::GetVectorAngleAbs(const Vector3D &a, const Vector3D &b) { + float cosine_vector_angle = Math::CosineVectorAngle(a, b); + return std::acos(cosine_vector_angle); + } + + float Math::GetVectorAngle(const Vector3D &a, const Vector3D &b) { + auto const a_unit = a.MakeUnitVector(); + auto const b_unit = b.MakeUnitVector(); + auto const cosine_vector_angle = Math::CosineVectorAngleFromUnitVectors(a_unit, b_unit); + auto const sine_vector_angle = Math::SineVectorAngleFromUnitVectors(a_unit, b_unit); + auto const angle = std::atan2(sine_vector_angle, cosine_vector_angle); + return angle; } std::pair Math::DistanceSegmentToPoint( @@ -114,39 +140,17 @@ namespace geom { return Vector3D(p.x * c - p.y * s, p.x * s + p.y * c, 0.0f); } - Vector3D Math::GetForwardVector(const Rotation &rotation) { - const float cp = std::cos(ToRadians(rotation.pitch)); - const float sp = std::sin(ToRadians(rotation.pitch)); - const float cy = std::cos(ToRadians(rotation.yaw)); - const float sy = std::sin(ToRadians(rotation.yaw)); - return {cy * cp, sy * cp, sp}; - } + Vector3D GetForwardVector(const Rotation &rotation) { return rotation.GetForwardVector(); } - Vector3D Math::GetRightVector(const Rotation &rotation) { - const float cy = std::cos(ToRadians(rotation.yaw)); - const float sy = std::sin(ToRadians(rotation.yaw)); - const float cr = std::cos(ToRadians(rotation.roll)); - const float sr = std::sin(ToRadians(rotation.roll)); - const float cp = std::cos(ToRadians(rotation.pitch)); - const float sp = std::sin(ToRadians(rotation.pitch)); - return { - cy * sp * sr - sy * cr, - sy * sp * sr + cy * cr, - -cp * sr}; - } + Vector3D GetRightVector(const Rotation &rotation) { return rotation.GetRightVector(); } - Vector3D Math::GetUpVector(const Rotation &rotation) { - const float cy = std::cos(ToRadians(rotation.yaw)); - const float sy = std::sin(ToRadians(rotation.yaw)); - const float cr = std::cos(ToRadians(rotation.roll)); - const float sr = std::sin(ToRadians(rotation.roll)); - const float cp = std::cos(ToRadians(rotation.pitch)); - const float sp = std::sin(ToRadians(rotation.pitch)); - return { - -cy * sp * cr - sy * sr, - -sy * sp * cr + cy * sr, - cp * cr}; - } + Vector3D GetUpVector(const Rotation &rotation) { return rotation.GetUpVector(); } + + Vector3D GetForwardVector(const Quaternion &quaternion) { return quaternion.GetForwardVector(); } + + Vector3D GetRightVector(const Quaternion &quaternion) { return quaternion.GetRightVector(); } + + Vector3D GetUpVector(const Quaternion &quaternion) { return quaternion.GetUpVector(); } std::vector Math::GenerateRange(int a, int b) { std::vector result; diff --git a/LibCarla/source/carla/geom/Math.h b/LibCarla/source/carla/geom/Math.h index fa25c2b7766..046fe199f9f 100644 --- a/LibCarla/source/carla/geom/Math.h +++ b/LibCarla/source/carla/geom/Math.h @@ -17,6 +17,7 @@ namespace carla { namespace geom { class Rotation; + class Quaternion; class Math { public: @@ -33,6 +34,12 @@ namespace geom { return static_cast(static_cast(2) * Pi()); } + template + static constexpr T Pi_2() { + static_assert(std::is_floating_point::value, "type must be floating point"); + return static_cast(static_cast(0.5) * Pi()); + } + template static constexpr T ToDegrees(T rad) { static_assert(std::is_floating_point::value, "type must be floating point"); @@ -63,6 +70,10 @@ namespace geom { return a.x * b.x + a.y * b.y + a.z * b.z; } + static auto Length(const Vector3D &a) { + return std::sqrt(Math::Dot(a, a)); + } + static auto Dot2D(const Vector3D &a, const Vector3D &b) { return a.x * b.x + a.y * b.y; } @@ -87,8 +98,11 @@ namespace geom { return a * (1.0f - f) + (b * f); } - /// Returns the angle between 2 vectors in radians - static double GetVectorAngle(const Vector3D &a, const Vector3D &b); + /// Returns the angle between 2 vectors in radians in [-PI; PI] + static float GetVectorAngle(const Vector3D &a, const Vector3D &b); + + /// Returns the abs angle between 2 vectors in radians in [0; PI] + static float GetVectorAngleAbs(const Vector3D &a, const Vector3D &b); /// Returns a pair containing: /// - @b first: distance from v to p' where p' = p projected on segment @@ -124,9 +138,133 @@ namespace geom { /// Compute the unit vector pointing towards the Y-axis of @a rotation. static Vector3D GetUpVector(const Rotation &rotation); + /// Compute the unit vector pointing towards the X-axis of @a quaternion. + static Vector3D GetForwardVector(const Quaternion &quaternion); + + /// Compute the unit vector pointing towards the Y-axis of @a quaternion. + static Vector3D GetRightVector(const Quaternion &quaternion); + + /// Compute the unit vector pointing towards the Y-axis of @a quaternion. + static Vector3D GetUpVector(const Quaternion &quaternion); + // Helper function to generate a vector of consecutive integers from a to b static std::vector GenerateRange(int a, int b); + /** Returns the cosine of the angle between the two unit vectors + * + * This is based on the DotProduct() of the vectors + * (a * b)/(||a|| * ||b||)= cos(phi) + * + * Be aware: use this optimized function if you are sure that vectors a_unit and b_unit are actually a unit vectors! + * + * \param a_unit must be a unit vector + * \param b_unit must be a unit vector + * + * \returns The cosine of the angle between the two given unit vectors + */ + static float CosineVectorAngleFromUnitVectors(Vector3D const &a_unit, Vector3D const &b_unit) + { + return Dot(a_unit, b_unit); + } + + /** Returns the cosine of the angle between the two vectors + * + * This is based on the DotProduct() of the vectors + * (a * b)/(||a|| * ||b||)= cos(phi) + * + * \param a just a vector + * \param b another vector + * + * \returns The cosine of the angle between the two given vectors + */ + static float CosineVectorAngle(Vector3D const &a, Vector3D const &b) + { + return CosineVectorAngleFromUnitVectors(a.MakeUnitVector(), b.MakeUnitVector()); + } + + /** Returns the absolute of the sine of the angle between the two vectors + * + * This is based on the Cross() of the vectors + * a x b = ||a|| * ||b|| * sin(phi) * n + * with n being the unit vector of the vector with right angles to both a and b + * + * \param a just a vector + * \param b another vector + * + * \returns The absolute of the sine of the angle between the two given vectors + */ + static float SineVectorAngleAbs(Vector3D const &a, Vector3D const &b) + { + return Math::Length(Math::Cross(a.MakeUnitVector(), b.MakeUnitVector())); + } + + /** Returns the sine of the angle between the two unit vectors whereas the sign is dertermined in respect to the up-vector + * + * This is based on the Cross() of the vectors + * a x b = ||a|| * ||b|| * sin(phi) * n + * with n being the unit vector of the vector with right angles to both a and b + * + * Be aware: use this optimized function if you are sure that vectors a_unit and b_unit are actually a unit vectors! + * + * \param a_unit must be a unit vector + * \param b_unit must be a unit vector + * + * \returns The absolute of the sine of the angle between the two given vectors + */ + static float SineVectorAngleFromUnitVectors(Vector3D const &a_unit, Vector3D const &b_unit); + + /** Returns the sine of the angle between the two vectors whereas the sign is dertermined in respect to the up-vector + * + * This is based on the Cross() of the vectors + * a x b = ||a|| * ||b|| * sin(phi) * n + * with n being the unit vector of the vector with right angles to both a and b + * + * \param a just a vector + * \param b another vector + * + * \returns The absolute of the sine of the angle between the two given vectors + */ + static float SineVectorAngle(Vector3D const &a, Vector3D const &b) + { + return SineVectorAngleFromUnitVectors(a.MakeUnitVector(), b.MakeUnitVector()); + } + + /** Returns the signbit of the cosine of the angle between vector \c a and unit vector \c b_unit + * + * This is based on the DotProdcut() of the vectors + * a⋅(b/||b||)=||a|| cos(phi) + * + * \param a just a vector + * \param b_unit must be a unit vector + * + * \returns the signbit of the cosine of the angle between a vector and a unit vectors (Be aware: +0.f returns \c false, -0.f returns \c true) + * \retval \c false The vectors are pointing within the same half plane (||phi|| <= M_PI_2) i.e. pointing into "same direction" + * \retval \c true The vectors are pointing the same half plane (||phi|| >= M_PI_2) i.e. pointing into "opposite direction" + * + * Be aware: use this optimized function if you are sure that vector b_unit is actually a unit vector! + */ + static bool SignBitCosineAngleFromUnitVector(Vector3D const &a, Vector3D const &b_unit) + { + return std::signbit(Dot(a, b_unit)); + } + + /** Returns the signbit of the cosine of the angle between two vectors + * + * This is based on the DotProdcut() of the vectors + * a⋅(b/||b||)=||a|| cos(phi) + * + * \param a just a vector + * \param b another vector + * + * \returns the signbit of the cosine of the angle between the two vectors (Be aware: +0.f returns \c false, -0.f returns \c true) + * \retval \c false The vectors are pointing within the same half plane (||phi|| <= M_PI_2) i.e. pointing into "same direction" + * \retval \c true The vectors are pointing the same half plane (||phi|| >= M_PI_2) i.e. pointing into "opposite direction" + */ + static bool SignBitCosineAngle(Vector3D const &a, Vector3D const &b) + { + return SignBitCosineAngleFromUnitVector(a, b.MakeUnitVector()); + } + }; } // namespace geom } // namespace carla diff --git a/LibCarla/source/carla/geom/Quaternion.h b/LibCarla/source/carla/geom/Quaternion.h new file mode 100644 index 00000000000..0c2a0ecde3c --- /dev/null +++ b/LibCarla/source/carla/geom/Quaternion.h @@ -0,0 +1,389 @@ +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#define ALLOW_UNSAFE_GEOM_MATRIX_ACCESS 1 + +#include + +#include "carla/MsgPack.h" +#include "carla/geom/Math.h" +#include "carla/geom/Location.h" +#include "carla/geom/Vector3D.h" +#include "carla/geom/Rotation.h" +#include "carla/geom/RightHandedVector3D.h" + +namespace carla { +namespace geom { + + class Quaternion; + class Transform; + + Quaternion operator*(const Quaternion& q1, const Quaternion& q2); + Quaternion operator*(const Quaternion& q, const Vector3D& w); + Quaternion operator*(const Vector3D& w, const Quaternion& q); + Quaternion operator*(const Quaternion& q1, const float& s); + + /** + * Stores the orientation of an entity as quaternion; + * The quaternion is existing in Unreal coordinate system. + * This is considered by all defined operations on the quaternion (input/output vectors and angles are automatically converted where required) + * + * Be aware: UE uses left-handed coordinate system! + Because nearly every writing on this is written in a form which let's room for interpretation + Even that one talks on clock-wise rotation: https://forums.unrealengine.com/t/ue4-coordinate-system-not-right-handed/80398/4, + but it is not telling if you are watching into axis positive direction or negative direction; therefore "clockwise" can be interpreted in both ways. + Ok, the example given makes it definitely clear then. + + Therefore let's take the easiest way to explain: Your left hand! + Point thumb upwards (positive z-Axis direction), index finger forwards (positive x-Axis direction), middle finger rightwards (positive y-Axis direction) + Positive rotation can be "visualized" with thumb of the left hand pointing into the respective positive direction of the rotation axis, + then the fingers when creating a fist are showing the positive rotation direction. + + The same by the way, works for right-handed coordinate systems: just take the right hand instead, resulting in the y-axis beeing flipped and rotation direction switches! + + The "problem" is that a linear algebra (matrix/quaternion/vector multiplication) is actually operating in a right-handed coordinate system. Don't ask why the hell the + compter graphics guys actually prefer left-handed systems. Robotics, of which automated driving is a sub area, does not. + */ + class Quaternion { + public: + + // ========================================================================= + // -- Public data members -------------------------------------------------- + // ========================================================================= + + float x = 0.0f; + + float y = 0.0f; + + float z = 0.0f; + + float w = 1.0f; + + // ========================================================================= + // -- Constructors and "Creators" --------------------------------------------------------- + // ========================================================================= + + Quaternion(float x_ = 0.f, float y_= 0.f, float z_= 0.f, float w_= 1.f) + : x(x_), + y(y_), + z(z_), + w(w_) {} + + explicit Quaternion(Rotation const &rotator) { + // intermediate values in double to improve precision + // calculation see https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles + double const roll_2 = Math::ToRadians(rotator.roll) * 0.5; + double const pitch_2 = Math::ToRadians(rotator.pitch) * 0.5; + double const yaw_2 = Math::ToRadians(rotator.yaw) * 0.5; + double cr = std::cos(roll_2); + double sr = std::sin(roll_2); + double cp = std::cos(pitch_2); + double sp = std::sin(pitch_2); + double cy = std::cos(yaw_2); + double sy = std::sin(yaw_2); + + // unreal rotates in counter direction, therefore the rotation has to be inverted. + // Unreal uses left handed system: negate x,y,z axis (counter direction), negate y-axis (pointing to the right) + x = -float(sr * cp * cy - cr * sp * sy); // negate + y = float(cr * sp * cy + sr * cp * sy); // double negate + z = -float(cr * cp * sy - sr * sp * cy); // negate + w = float(cr * cp * cy + sr * sp * sy); + } + + static Quaternion CreateFromYawDegree(float const &yaw_degree) { + // intermediate values in double to improve precision + // calculation see https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles + // unreal rotates in left direction ! therefore we have to apply the inverse Euler rotation here + double const yaw_2 = Math::ToRadians(yaw_degree) * 0.5; + double cy = std::cos(yaw_2); + double sy = std::sin(yaw_2); + Quaternion quat; + // unreal rotates in counter direction, therefore the rotation has to be inverted. + // Unreal uses left handed system: y-axis is negated (double negated) + quat.x = 0.f; + quat.y = 0.f; + quat.z = -float(sy); // negate + quat.w = float(cy); + return quat; + } + + static Quaternion Identity() { return Quaternion(); } + + // ========================================================================= + // -- Other methods -------------------------------------------------------- + // ========================================================================= + + /// Compute the unit vector pointing towards the X-axis of the rotation described by this quaternion. + Vector3D GetForwardVector() const { + Vector3D const forward_vector(1.0, 0.0, 0.0); + return RotatedVector(forward_vector); + } + + /// Compute the unit vector pointing towards the Y-axis of of the rotation described by this quaternion. + Vector3D GetRightVector() const { + Vector3D const right_vector(0.0, 1.0, 0.0); + return RotatedVector(right_vector); + } + + /// Compute the unit vector pointing towards the Z-axis of of the rotation described by this quaternion. + Vector3D GetUpVector() const { + Vector3D const up_vector(0.0, 0.0, 1.0); + return RotatedVector(up_vector); + } + + Quaternion Inverse() const { + return Quaternion(-x, -y, -z, w); + } + + float Length() const { + return std::sqrt(SquaredLength()); + } + + float SquaredLength() const { + return x * x + y * y + z * z + w * w; + } + + Quaternion UnitQuaternion() const { + auto const d = Length(); + Quaternion unit_quat = *this * d; + return unit_quat; + } + + /* Return this quaternion rotated by the give quaternion \c q */ + Quaternion RotatedQuaternion(Quaternion const &q) const { + return q * *this * q.Inverse(); + } + + /** shortened version of Rotator() providing the yaw component in rad + */ + float YawRad() const { + auto const matrix = RotationMatrix(); + float yaw = 0.f; + if (std::abs(matrix[6]) < 1.f) { + auto const pitch = -std::asin(matrix[6]); + auto const cp = std::cos(pitch); + yaw = std::atan2(matrix[3]/cp, matrix[0]/cp); + } + // Unreal uses left handed system: y-axis is negated: apply on output vector + return -yaw; + } + + /** shortened version of Rotator() providing the yaw component in degree + */ + float YawDegree() const { + return Math::ToDegrees(YawRad()); + } + + carla::geom::Rotation Rotator() const { + // calculation see https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles + auto const matrix = RotationMatrix(); + float yaw = 0.f; + float pitch = 0.f; + float roll = 0.f; + if (std::abs(matrix[6]) < 1.f) { + pitch = -std::asin(matrix[6]); + auto const cp = std::cos(pitch); + yaw = std::atan2(matrix[3]/cp, matrix[0]/cp); + roll = std::atan2(matrix[7]/cp, matrix[8]/cp); + } + else { + // singularity + if ( std::signbit(matrix[6]) ) { + // gimbal lock up + pitch = Math::Pi_2(); + } + else { + // gimbal lock down + pitch = -Math::Pi_2(); + } + yaw = 0.f; + roll = std::atan2(matrix[7], matrix[8]); + } + // Unreal uses left handed system: negate all rotations + carla::geom::Rotation rotator; + rotator.roll = Math::ToDegrees(-roll); + rotator.pitch = Math::ToDegrees(-pitch); + rotator.yaw = Math::ToDegrees(-yaw); + return rotator; + } + + template + RightHandedVector3D RotatedVector(VECTOR_TYPE const &in_point) const { + return RotatedPoint(in_point); + } + + template + RightHandedVector3D InverseRotatedVector(VECTOR_TYPE const &in_point) const { + return InverseRotatedPoint(in_point); + } + + // ========================================================================= + // -- Comparison operators ------------------------------------------------- + // ========================================================================= + + bool operator==(const Quaternion &rhs) const { + return (x == rhs.x) && (y == rhs.y) && (z == rhs.z) && (w == rhs.w); + } + + bool operator!=(const Quaternion &rhs) const { + return !(*this == rhs); + } + + // ========================================================================= + // -- Conversions to UE4 types --------------------------------------------- + // ========================================================================= + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + Quaternion(const FQuat &quat) + : x(quat.X) + , y(quat.Y) + , z(quat.Z) + , w(quat.W) {} + + operator FQuat() const { + FQuat quat; + quat.X = x; + quat.Y = y; + quat.Z = z; + quat.W = w; + return quat; + } + +#endif // LIBCARLA_INCLUDED_FROM_UE4 + + + // ========================================================================= + /// @todo The following is copy-pasted from MSGPACK_DEFINE_ARRAY. + /// This is a workaround for an issue in msgpack library. The + /// MSGPACK_DEFINE_ARRAY macro is shadowing our `z` variable. + /// https://github.com/msgpack/msgpack-c/issues/709 + // ========================================================================= + template + void msgpack_pack(Packer& pk) const + { + clmdep_msgpack::type::make_define_array(x, y, z, w).msgpack_pack(pk); + } + void msgpack_unpack(clmdep_msgpack::object const& o) + { + clmdep_msgpack::type::make_define_array(x, y, z, w).msgpack_unpack(o); + } + template + void msgpack_object(MSGPACK_OBJECT* o, clmdep_msgpack::zone& sneaky_variable_that_shadows_z) const + { + clmdep_msgpack::type::make_define_array(x, y, z, w).msgpack_object(o, sneaky_variable_that_shadows_z); + } + // ========================================================================= + +#if ALLOW_UNSAFE_GEOM_MATRIX_ACCESS + public: +#else + private: +#endif + // Computes the 3x3 rotation-matrix of the quaternion (as this matrix operates in right handed space as our quaternion, keept the matrix private for the moment. + // If required public input/output vectors of this operation will have to be ensured to be RightHandedVector3D + // Therefore, making it public reuires a dedicated Matrix class which is enforing this by it's interface. + // Don't allow access on matrix members for people who don't know the background in detail: that will definitely go wrong! + // Best is to NOT use this function therefore at all. + std::array RotationMatrix() const { + // calculation see https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles + // in the matrix each component is multplied with another component; + // instead of dividing each component by the norm, and the multiply (and square the norm again), we can use the squard_norm immediately + // the factor of 2 can also be moved into the single components + auto const norm_squared = SquaredLength(); + auto const factor = 2.f / norm_squared; + auto const x2 = x * factor; + auto const y2 = y * factor; + auto const z2 = z * factor; + auto const wx2 = w * x2; + auto const wy2 = w * y2; + auto const wz2 = w * z2; + auto const xx2 = x * x2; + auto const xy2 = x * y2; + auto const xz2 = x * z2; + auto const yy2 = y * y2; + auto const yz2 = y * z2; + auto const zz2 = z * z2; + std::array matrix = { + float(1. - (yy2 + zz2)), + float(xy2 - wz2), + float(wy2 + xz2), + float(xy2 + wz2), + float(1. - (xx2 + zz2)), + float(yz2 - wx2), + float(xz2 - wy2), + float(wx2 + yz2), + float(1. - (xx2 + yy2))}; + return matrix; + } + + /// Computes the 3x3 rotation-matrix of the inverse quaternion + std::array InverseRotationMatrix() const { + return Inverse().RotationMatrix(); + } + + RightHandedVector3D RotatedPoint(RightHandedVector3D const &in_point) const { + Quaternion quat = *this * in_point * Inverse(); + RightHandedVector3D out_point; + out_point.x = quat.x; + out_point.y = quat.y; + out_point.z = quat.z; + return out_point; + } + + RightHandedVector3D InverseRotatedPoint(RightHandedVector3D const &in_point) const { + Quaternion quat = Inverse() * in_point * *this; + RightHandedVector3D out_point; + out_point.x = quat.x; + out_point.y = quat.y; + out_point.z = quat.z; + return out_point; + } + }; + + +inline Quaternion operator*(const Quaternion& q1, const Quaternion& q2) { + Quaternion quat; + quat.x = q1.w * q2.x + q1.x * q2.w + q1.y * q2.z - q1.z * q2.y; + quat.y = q1.w * q2.y + q1.y * q2.w + q1.z * q2.x - q1.x * q2.z; + quat.z = q1.w * q2.z + q1.z * q2.w + q1.x * q2.y - q1.y * q2.x; + quat.w = q1.w * q2.w - q1.x * q2.x - q1.y * q2.y - q1.z * q2.z; + return quat; +} + +inline Quaternion operator*(const Quaternion& q, const RightHandedVector3D& v) +{ + Quaternion quat; + quat.x = q.w * v.x + q.y * v.z - q.z * v.y; + quat.y = q.w * v.y + q.z * v.x - q.x * v.z; + quat.z = q.w * v.z + q.x * v.y - q.y * v.x; + quat.w = -q.x * v.x - q.y * v.y - q.z * v.z; + return quat; +} + +inline Quaternion operator*(const RightHandedVector3D& v, const Quaternion& q) +{ + Quaternion quat; + quat.x = v.x * q.w + v.y * q.z - v.z * q.y; + quat.y = v.y * q.w + v.z * q.x - v.x * q.z; + quat.z = v.z * q.w + v.x * q.y - v.y * q.x; + quat.w =-v.x * q.x - v.y * q.y - v.z * q.z; + return quat; +} + +inline Quaternion operator*(const Quaternion& q1, const float& s) { + Quaternion quat; + quat.w = q1.w * s; + quat.x = q1.x * s; + quat.y = q1.y * s; + quat.z = q1.z * s; + return quat; +} + +} // namespace geom +} // namespace carla diff --git a/LibCarla/source/carla/geom/RightHandedVector3D.h b/LibCarla/source/carla/geom/RightHandedVector3D.h new file mode 100644 index 00000000000..f931bc4744e --- /dev/null +++ b/LibCarla/source/carla/geom/RightHandedVector3D.h @@ -0,0 +1,54 @@ +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/geom/Vector3D.h" + +namespace carla { +namespace geom { + + class Quaternion; + class Rotation; + Quaternion operator*(const Quaternion& q, const Vector3D& w); + Quaternion operator*(const Vector3D& w, const Quaternion& q); + + /** Stores a Vector3D in right handed representation required for the internal calculations */ + class RightHandedVector3D { + public: + RightHandedVector3D(Vector3D const& ue_vector) + : x(ue_vector.x) + , y(-ue_vector.y) + , z(ue_vector.z) + {} + + operator Vector3D() const { + return Vector3D(x, -y, z); + } + + private: + // only the implicit conversion's are accessible by the public + RightHandedVector3D() = default; + RightHandedVector3D(RightHandedVector3D const &) = default; + RightHandedVector3D(RightHandedVector3D &&) = default; + RightHandedVector3D& operator=(RightHandedVector3D const &) = default; + RightHandedVector3D& operator=(RightHandedVector3D &&) = default; + + friend class Quaternion; + friend class Rotation; + friend Quaternion operator*(const Quaternion&, const RightHandedVector3D&); + friend Quaternion operator*(const RightHandedVector3D&, const Quaternion&); + + + float x = 0.0f; + + float y = 0.0f; + + float z = 0.0f; + }; + +} // namespace geom +} // namespace carla diff --git a/LibCarla/source/carla/geom/Rotation.h b/LibCarla/source/carla/geom/Rotation.h index 784a57fcabb..1ec37348307 100644 --- a/LibCarla/source/carla/geom/Rotation.h +++ b/LibCarla/source/carla/geom/Rotation.h @@ -9,6 +9,7 @@ #include "carla/MsgPack.h" #include "carla/geom/Math.h" #include "carla/geom/Vector3D.h" +#include "carla/geom/RightHandedVector3D.h" #ifdef LIBCARLA_INCLUDED_FROM_UE4 #include @@ -19,6 +20,10 @@ namespace carla { namespace geom { + + /** + * Class representing the UE4 Rotator (RPY in degrees) + */ class Rotation { public: @@ -49,79 +54,82 @@ namespace geom { // -- Other methods -------------------------------------------------------- // ========================================================================= + /// Compute the unit vector pointing towards the X-axis of the rotation described by this rotator. Vector3D GetForwardVector() const { - return Math::GetForwardVector(*this); + Vector3D const forward_vector(1.0, 0.0, 0.0); + return RotatedVector(forward_vector); } + /// Compute the unit vector pointing towards the Y-axis of of the rotation described by this rotator. Vector3D GetRightVector() const { - return Math::GetRightVector(*this); + Vector3D const right_vector(0.0, 1.0, 0.0); + return RotatedVector(right_vector); } + /// Compute the unit vector pointing towards the Z-axis of of the rotation described by this rotator. Vector3D GetUpVector() const { - return Math::GetUpVector(*this); + Vector3D const up_vector(0.0, 0.0, 1.0); + return RotatedVector(up_vector); } - void RotateVector(Vector3D &in_point) const { + RightHandedVector3D RotatedVector(RightHandedVector3D const &in_point) const { // Rotates Rz(yaw) * Ry(pitch) * Rx(roll) = first x, then y, then z. - const float cy = std::cos(Math::ToRadians(yaw)); - const float sy = std::sin(Math::ToRadians(yaw)); - const float cr = std::cos(Math::ToRadians(roll)); - const float sr = std::sin(Math::ToRadians(roll)); - const float cp = std::cos(Math::ToRadians(pitch)); - const float sp = std::sin(Math::ToRadians(pitch)); - - Vector3D out_point; + // Unreal uses left handed system: negate x,y,z axis rotations (counter direction), negate y-axis rotation again, because we have a right handed vector at hand now + const float cr = std::cos(Math::ToRadians(-roll)); // negate + const float sr = std::sin(Math::ToRadians(-roll)); // negate + const float cp = std::cos(Math::ToRadians(pitch)); // double-negate + const float sp = std::sin(Math::ToRadians(pitch)); // double-negate + const float cy = std::cos(Math::ToRadians(-yaw)); // negate + const float sy = std::sin(Math::ToRadians(-yaw)); // negate + + // Matrix basis see https://en.wikipedia.org/wiki/Rotation_matrix Euler Angles, alpha=roll, beta=pitch, gamma=yaw + RightHandedVector3D out_point; out_point.x = in_point.x * (cp * cy) + - in_point.y * (cy * sp * sr - sy * cr) + - in_point.z * (-cy * sp * cr - sy * sr); + in_point.y * (cy * sp * sr - sy * cr) + + in_point.z * (cy * sp * cr + sy * sr); out_point.y = in_point.x * (cp * sy) + in_point.y * (sy * sp * sr + cy * cr) + - in_point.z * (-sy * sp * cr + cy * sr); + in_point.z * (sy * sp * cr - cy * sr); out_point.z = - in_point.x * (sp) + - in_point.y * (-cp * sr) + + in_point.x * (-sp) + + in_point.y * (cp * sr) + in_point.z * (cp * cr); - in_point = out_point; - } - - Vector3D RotateVector(const Vector3D& in_point) const { - Vector3D out_point = in_point; - RotateVector(out_point); return out_point; } - void InverseRotateVector(Vector3D &in_point) const { + RightHandedVector3D InverseRotatedVector(RightHandedVector3D const &in_point) const { + // Unreal uses left handed system: negate x,y,z axis rotations (counter direction), negate y-axis rotation again, because we have a right handed vector at hand now + const float cr = std::cos(Math::ToRadians(-roll)); // negate + const float sr = std::sin(Math::ToRadians(-roll)); // negate + const float cp = std::cos(Math::ToRadians(pitch)); // double-negate + const float sp = std::sin(Math::ToRadians(pitch)); // double-negate + const float cy = std::cos(Math::ToRadians(-yaw)); // negate + const float sy = std::sin(Math::ToRadians(-yaw)); // negate + // Applies the transposed of the matrix used in RotateVector function, // which is the rotation inverse. - const float cy = std::cos(Math::ToRadians(yaw)); - const float sy = std::sin(Math::ToRadians(yaw)); - const float cr = std::cos(Math::ToRadians(roll)); - const float sr = std::sin(Math::ToRadians(roll)); - const float cp = std::cos(Math::ToRadians(pitch)); - const float sp = std::sin(Math::ToRadians(pitch)); - - Vector3D out_point; + RightHandedVector3D out_point; out_point.x = in_point.x * (cp * cy) + in_point.y * (cp * sy) + - in_point.z * (sp); + in_point.z * (-sp); out_point.y = in_point.x * (cy * sp * sr - sy * cr) + in_point.y * (sy * sp * sr + cy * cr) + - in_point.z * (-cp * sr); + in_point.z * (cp * sr); out_point.z = - in_point.x * (-cy * sp * cr - sy * sr) + - in_point.y * (-sy * sp * cr + cy * sr) + + in_point.x * (cy * sp * cr + sy * sr) + + in_point.y * (sy * sp * cr - cy * sr) + in_point.z * (cp * cr); - in_point = out_point; + return out_point; } // ========================================================================= @@ -153,4 +161,4 @@ namespace geom { }; } // namespace geom -} // namespace carla +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/geom/Transform.h b/LibCarla/source/carla/geom/Transform.h index 5cc07ed1b40..ab3e24160c4 100644 --- a/LibCarla/source/carla/geom/Transform.h +++ b/LibCarla/source/carla/geom/Transform.h @@ -9,6 +9,7 @@ #include "carla/MsgPack.h" #include "carla/geom/Location.h" #include "carla/geom/Math.h" +#include "carla/geom/Quaternion.h" #include "carla/geom/Rotation.h" #ifdef LIBCARLA_INCLUDED_FROM_UE4 @@ -39,7 +40,7 @@ namespace geom { Transform() = default; - Transform(const Location &in_location) + explicit Transform(const Location &in_location) : location(in_location), rotation() {} @@ -65,74 +66,19 @@ namespace geom { /// Applies this transformation to @a in_point (first translation then rotation). void TransformPoint(Vector3D &in_point) const { - auto out_point = in_point; - rotation.RotateVector(out_point); // First rotate - out_point += location; // Then translate - in_point = out_point; + Vector3D out_point = rotation.RotatedVector(in_point); // First rotate + in_point = out_point + Vector3D(location); // Then translate } /// Applies this transformation to @a in_vector (rotation only). void TransformVector(Vector3D &in_vector) const { - auto out_vector = in_vector; - rotation.RotateVector(out_vector); // First rotate - in_vector = out_vector; + in_vector = rotation.RotatedVector(in_vector); // Only rotation } /// Applies the inverse of this transformation to @a in_point void InverseTransformPoint(Vector3D &in_point) const { - auto out_point = in_point; - out_point -= location; // First translate inverse - rotation.InverseRotateVector(out_point); // Then rotate inverse - in_point = out_point; - } - - /// Computes the 4-matrix form of the transformation - std::array GetMatrix() const { - const float yaw = rotation.yaw; - const float cy = std::cos(Math::ToRadians(yaw)); - const float sy = std::sin(Math::ToRadians(yaw)); - - const float roll = rotation.roll; - const float cr = std::cos(Math::ToRadians(roll)); - const float sr = std::sin(Math::ToRadians(roll)); - - const float pitch = rotation.pitch; - const float cp = std::cos(Math::ToRadians(pitch)); - const float sp = std::sin(Math::ToRadians(pitch)); - - std::array transform = { - cp * cy, cy * sp * sr - sy * cr, -cy * sp * cr - sy * sr, location.x, - cp * sy, sy * sp * sr + cy * cr, -sy * sp * cr + cy * sr, location.y, - sp, -cp * sr, cp * cr, location.z, - 0.0, 0.0, 0.0, 1.0}; - - return transform; - } - - /// Computes the 4-matrix form of the inverse transformation - std::array GetInverseMatrix() const { - const float yaw = rotation.yaw; - const float cy = std::cos(Math::ToRadians(yaw)); - const float sy = std::sin(Math::ToRadians(yaw)); - - const float roll = rotation.roll; - const float cr = std::cos(Math::ToRadians(roll)); - const float sr = std::sin(Math::ToRadians(roll)); - - const float pitch = rotation.pitch; - const float cp = std::cos(Math::ToRadians(pitch)); - const float sp = std::sin(Math::ToRadians(pitch)); - - Vector3D a = {0.0f, 0.0f, 0.0f}; - InverseTransformPoint(a); - - std::array transform = { - cp * cy, cp * sy, sp, a.x, - cy * sp * sr - sy * cr, sy * sp * sr + cy * cr, -cp * sr, a.y, - -cy * sp * cr - sy * sr, -sy * sp * cr + cy * sr, cp * cr, a.z, - 0.0f, 0.0f, 0.0f, 1.0}; - - return transform; + Vector3D out_point = in_point - Vector3D(location); // First translate inverse + in_point = rotation.InverseRotatedVector(out_point); // Then rotate inverse } // ========================================================================= @@ -162,6 +108,38 @@ namespace geom { } #endif // LIBCARLA_INCLUDED_FROM_UE4 + +#if ALLOW_UNSAFE_GEOM_MATRIX_ACCESS + // this matrix is rotating within a right handed-coordinate system, but Unreal coordinate frame is left-handed! + // If we want to make this public, a dedicated Matrix4x4 type has to be defined considiering that (see also Quaternion.h) + std::array TransformationMatrix() const { + auto const matrix = Quaternion(rotation).RotationMatrix(); + + std::array transform = { + matrix[0], matrix[1], matrix[2], location.x, + matrix[3], matrix[4], matrix[5], location.y, + matrix[6], matrix[7], matrix[8], location.z, + 0.0, 0.0, 0.0, 1.0}; + + return transform; + } + + /// Computes the 4-matrix form of the inverse transformation + std::array InverseTransformationMatrix() const { + auto const matrix = Quaternion(rotation).InverseRotationMatrix(); + + Vector3D a = {0.0f, 0.0f, 0.0f}; + InverseTransformPoint(a); + + std::array transform = { + matrix[0], matrix[1], matrix[2], a.x, + matrix[3], matrix[4], matrix[5], a.y, + matrix[6], matrix[7], matrix[8], a.z, + 0.0f, 0.0f, 0.0f, 1.0}; + + return transform; + } +#endif }; } // namespace geom diff --git a/LibCarla/source/carla/geom/Vector2D.h b/LibCarla/source/carla/geom/Vector2D.h index d5252f5894c..8aace913c4b 100644 --- a/LibCarla/source/carla/geom/Vector2D.h +++ b/LibCarla/source/carla/geom/Vector2D.h @@ -39,6 +39,10 @@ namespace geom { // -- Other methods -------------------------------------------------------- // ========================================================================= + double ExactLength() const { + return std::sqrt(double(x) * x + double(y) * y); + } + float SquaredLength() const { return x * x + y * y; } @@ -47,11 +51,24 @@ namespace geom { return std::sqrt(SquaredLength()); } - Vector2D MakeUnitVector() const { - const float len = Length(); - DEVELOPMENT_ASSERT(len > 2.0f * std::numeric_limits::epsilon()); - const float k = 1.0f / len; - return Vector2D(x * k, y * k); + Vector2D MakeUnitVectorLengthInput(const double length, const float epsilon = 2.0f * std::numeric_limits::epsilon()) const { + if (length < epsilon) { + return *this; + } + const double k = 1.0 / length; + Vector2D result(float(x * k), float(y * k)); + return result; + } + + Vector2D MakeUnitVector(const float epsilon = 2.0f * std::numeric_limits::epsilon()) const { + const double length = ExactLength(); + return MakeUnitVectorLengthInput(length, epsilon); + } + + std::pair GetUnitVectorAndLength() const { + const auto length = ExactLength(); + const auto unit_vector = MakeUnitVectorLengthInput(length); + return std::make_pair(unit_vector, length); } // ========================================================================= diff --git a/LibCarla/source/carla/geom/Vector3D.h b/LibCarla/source/carla/geom/Vector3D.h index 361e81af48d..2057fd56ad6 100644 --- a/LibCarla/source/carla/geom/Vector3D.h +++ b/LibCarla/source/carla/geom/Vector3D.h @@ -50,6 +50,10 @@ namespace geom { return std::sqrt(SquaredLength()); } + double ExactLength() const { + return std::sqrt(double(x) * x + double(y) * y + double(z) * z); + } + float SquaredLength2D() const { return x * x + y * y; } @@ -62,17 +66,25 @@ namespace geom { return Vector3D(abs(x), abs(y), abs(z)); } - Vector3D MakeUnitVector() const { - const float length = Length(); - DEVELOPMENT_ASSERT(length > 2.0f * std::numeric_limits::epsilon()); - const float k = 1.0f / length; - return Vector3D(x * k, y * k, z * k); + Vector3D MakeUnitVectorLengthInput(const double length, const float epsilon = 2.0f * std::numeric_limits::epsilon()) const { + if (length < epsilon) { + DEVELOPMENT_ASSERT(length >= 2.0f * std::numeric_limits::epsilon()); + return *this; + } + const double k = 1.0 / length; + Vector3D result(float(x * k), float(y * k), float(z * k)); + return result; + } + + Vector3D MakeUnitVector(const float epsilon = 2.0f * std::numeric_limits::epsilon()) const { + const double length = ExactLength(); + return MakeUnitVectorLengthInput(length, epsilon); } - Vector3D MakeSafeUnitVector(const float epsilon) const { - const float length = Length(); - const float k = (length > std::max(epsilon, 0.0f)) ? (1.0f / length) : 1.0f; - return Vector3D(x * k, y * k, z * k); + std::pair GetUnitVectorAndLength() const { + const auto length = ExactLength(); + const auto unit_vector = MakeUnitVectorLengthInput(length); + return std::make_pair(unit_vector, length); } // ========================================================================= diff --git a/LibCarla/source/carla/geom/Velocity.h b/LibCarla/source/carla/geom/Velocity.h new file mode 100644 index 00000000000..46c58a19693 --- /dev/null +++ b/LibCarla/source/carla/geom/Velocity.h @@ -0,0 +1,117 @@ +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/geom/Vector3D.h" +#include "carla/geom/Vector3DInt.h" +#include "carla/geom/Math.h" +#include "carla/geom/Quaternion.h" + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 +#include +#include "Math/Vector.h" +#include +#endif // LIBCARLA_INCLUDED_FROM_UE4 + +namespace carla { +namespace geom { + + class Velocity : public Vector3D { + public: + + // ========================================================================= + // -- Constructors --------------------------------------------------------- + // ========================================================================= + + Velocity() = default; + + using Vector3D::Vector3D; + + Velocity(const Vector3D &rhs) : Vector3D(rhs) {} + + Velocity(const Vector3DInt &rhs) : + Vector3D(static_cast(rhs.x), + static_cast(rhs.y), + static_cast(rhs.z)) {} + + // ========================================================================= + // -- Other methods -------------------------------------------------------- + // ========================================================================= + + // return the signed speed of the velocity vector in reference to the provided orientation of the respective object + auto Speed(carla::geom::Quaternion const &orientation) const { + bool signbit_cosine = false; + auto const speed = Length(); + if ( speed > 1e-2 ) { + // decide if we are driving forward or backward by the cosine between forward vector and velocity vector + auto const forward_unit_vector = orientation.GetForwardVector(); + signbit_cosine = carla::geom::Math::SignBitCosineAngleFromUnitVector(*this, forward_unit_vector); + } + if ( signbit_cosine ) { + return -speed; + } + else { + return speed; + } + } + + // ========================================================================= + // -- Arithmetic operators ------------------------------------------------- + // ========================================================================= + + Velocity &operator+=(const Velocity &rhs) { + static_cast(*this) += static_cast(rhs); + return *this; + } + + friend Velocity operator+(Velocity lhs, const Velocity &rhs) { + lhs += rhs; + return lhs; + } + + Velocity &operator-=(const Velocity &rhs) { + static_cast(*this) -= static_cast(rhs); + return *this; + } + + friend Velocity operator-(Velocity lhs, const Velocity &rhs) { + lhs -= rhs; + return lhs; + } + + // ========================================================================= + // -- Comparison operators ------------------------------------------------- + // ========================================================================= + + bool operator==(const Velocity &rhs) const { + return static_cast(*this) == static_cast(rhs); + } + + bool operator!=(const Velocity &rhs) const { + return !(*this == rhs); + } + + // ========================================================================= + // -- Conversions to UE4 types --------------------------------------------- + // ========================================================================= + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + // from cm/s to m/s. + Velocity(const FVector &vector) + : Velocity(1e-2f * vector.X, 1e-2f * vector.Y, 1e-2f * vector.Z) {} + + // from m/s to cm/s + operator FVector() const { + return FVector{1e2f * x, 1e2f * y, 1e2f * z}; + } + +#endif // LIBCARLA_INCLUDED_FROM_UE4 + }; + +} // namespace geom +} // namespace carla diff --git a/LibCarla/source/carla/multigpu/primary.cpp b/LibCarla/source/carla/multigpu/primary.cpp index e55ab53405e..e5a41d59290 100644 --- a/LibCarla/source/carla/multigpu/primary.cpp +++ b/LibCarla/source/carla/multigpu/primary.cpp @@ -65,7 +65,7 @@ namespace multigpu { ReadData(); } - void Primary::Write(std::shared_ptr message) { + void Primary::Write(std::shared_ptr message) { DEBUG_ASSERT(message != nullptr); DEBUG_ASSERT(!message->empty()); std::weak_ptr weak = shared_from_this(); diff --git a/LibCarla/source/carla/multigpu/primary.h b/LibCarla/source/carla/multigpu/primary.h index e2043f2113e..aa565802c45 100644 --- a/LibCarla/source/carla/multigpu/primary.h +++ b/LibCarla/source/carla/multigpu/primary.h @@ -11,7 +11,7 @@ #include "carla/TypeTraits.h" #include "carla/profiler/LifetimeProfiled.h" #include "carla/streaming/detail/Types.h" -#include "carla/streaming/detail/tcp/Message.h" +#include "carla/streaming/detail/Message.h" #include "carla/multigpu/listener.h" #include @@ -55,11 +55,11 @@ namespace multigpu { static_assert( are_same::value, "This function only accepts arguments of type BufferView."); - return std::make_shared(buffers...); + return std::make_shared(buffers...); } /// Writes some data to the socket. - void Write(std::shared_ptr message); + void Write(std::shared_ptr message); /// Writes a string void Write(std::string text); diff --git a/LibCarla/source/carla/multigpu/primaryCommands.cpp b/LibCarla/source/carla/multigpu/primaryCommands.cpp index ed1ab897f42..c9ae1332366 100644 --- a/LibCarla/source/carla/multigpu/primaryCommands.cpp +++ b/LibCarla/source/carla/multigpu/primaryCommands.cpp @@ -10,7 +10,7 @@ #include "carla/multigpu/commands.h" #include "carla/multigpu/primary.h" #include "carla/multigpu/router.h" -#include "carla/streaming/detail/tcp/Message.h" +#include "carla/streaming/detail/Message.h" #include "carla/streaming/detail/Token.h" #include "carla/streaming/detail/Types.h" @@ -41,9 +41,9 @@ void PrimaryCommands::SendLoadMap(std::string map) { } // send to who the router wants the request for a token -token_type PrimaryCommands::SendGetToken(stream_id sensor_id) { +token_type PrimaryCommands::SendGetToken(stream_id stream_id) { log_info("asking for a token"); - carla::Buffer buf((carla::Buffer::value_type *) &sensor_id, + carla::Buffer buf((carla::Buffer::value_type *) &stream_id, (size_t) sizeof(stream_id)); auto fut = _router->WriteToNext(MultiGPUCommand::GET_TOKEN, std::move(buf)); @@ -63,56 +63,56 @@ void PrimaryCommands::SendIsAlive() { log_info("response from alive command: ", response.buffer.data()); } -void PrimaryCommands::SendEnableForROS(stream_id sensor_id) { +void PrimaryCommands::SendEnableForROS(carla::streaming::detail::stream_actor_id_type stream_actor_id) { // search if the sensor has been activated in any secondary server - auto it = _servers.find(sensor_id); + auto it = _servers.find(stream_actor_id.stream_id); if (it != _servers.end()) { - carla::Buffer buf((carla::Buffer::value_type *) &sensor_id, - (size_t) sizeof(stream_id)); + carla::Buffer buf((carla::Buffer::value_type *) &stream_actor_id, + (size_t) (sizeof(stream_actor_id))); auto fut = _router->WriteToOne(it->second, MultiGPUCommand::ENABLE_ROS, std::move(buf)); auto response = fut.get(); bool res = (*reinterpret_cast(response.buffer.data())); } else { - log_error("enable_for_ros for sensor", sensor_id, " not found on any server"); + log_error("enable_for_ros for sensor", stream_actor_id.stream_id, " not found on any server"); } } -void PrimaryCommands::SendDisableForROS(stream_id sensor_id) { +void PrimaryCommands::SendDisableForROS(carla::streaming::detail::stream_actor_id_type stream_actor_id) { // search if the sensor has been activated in any secondary server - auto it = _servers.find(sensor_id); + auto it = _servers.find(stream_actor_id.stream_id); if (it != _servers.end()) { - carla::Buffer buf((carla::Buffer::value_type *) &sensor_id, - (size_t) sizeof(stream_id)); + carla::Buffer buf((carla::Buffer::value_type *) &stream_actor_id, + (size_t) (sizeof(stream_actor_id))); auto fut = _router->WriteToOne(it->second, MultiGPUCommand::DISABLE_ROS, std::move(buf)); auto response = fut.get(); bool res = (*reinterpret_cast(response.buffer.data())); } else { - log_error("disable_for_ros for sensor", sensor_id, " not found on any server"); + log_error("disable_for_ros for sensor", stream_actor_id.stream_id, " not found on any server"); } } -bool PrimaryCommands::SendIsEnabledForROS(stream_id sensor_id) { +bool PrimaryCommands::SendIsEnabledForROS(carla::streaming::detail::stream_actor_id_type stream_actor_id) { // search if the sensor has been activated in any secondary server - auto it = _servers.find(sensor_id); + auto it = _servers.find(stream_actor_id.stream_id); if (it != _servers.end()) { - carla::Buffer buf((carla::Buffer::value_type *) &sensor_id, - (size_t) sizeof(stream_id)); + carla::Buffer buf((carla::Buffer::value_type *) &stream_actor_id, + (size_t) (sizeof(stream_actor_id))); auto fut = _router->WriteToOne(it->second, MultiGPUCommand::IS_ENABLED_ROS, std::move(buf)); auto response = fut.get(); bool res = (*reinterpret_cast(response.buffer.data())); return res; } else { - log_error("is_enabled_for_ros for sensor", sensor_id, " not found on any server"); + log_error("is_enabled_for_ros for sensor", stream_actor_id.stream_id, " not found on any server"); return false; } } -token_type PrimaryCommands::GetToken(stream_id sensor_id) { +token_type PrimaryCommands::GetToken(stream_id stream_id) { // search if the sensor has been activated in any secondary server - auto it = _tokens.find(sensor_id); + auto it = _tokens.find(stream_id); if (it != _tokens.end()) { // return already activated sensor token log_debug("Using token from already activated sensor: ", it->second.get_stream_id(), ", ", it->second.get_port()); @@ -121,37 +121,37 @@ token_type PrimaryCommands::GetToken(stream_id sensor_id) { else { // enable the sensor on one secondary server auto server = _router->GetNextServer(); - auto token = SendGetToken(sensor_id); + auto token = SendGetToken(stream_id); // add to the maps - _tokens[sensor_id] = token; - _servers[sensor_id] = server; + _tokens[stream_id] = token; + _servers[stream_id] = server; log_debug("Using token from new activated sensor: ", token.get_stream_id(), ", ", token.get_port()); return token; } } -void PrimaryCommands::EnableForROS(stream_id sensor_id) { - auto it = _servers.find(sensor_id); +void PrimaryCommands::EnableForROS(carla::streaming::detail::stream_actor_id_type stream_actor_id) { + auto it = _servers.find(stream_actor_id.stream_id); if (it != _servers.end()) { - SendEnableForROS(sensor_id); + SendEnableForROS(stream_actor_id); } else { // we need to activate the sensor in any server yet, and repeat - GetToken(sensor_id); - EnableForROS(sensor_id); + GetToken(stream_actor_id.stream_id); + EnableForROS(stream_actor_id); } } -void PrimaryCommands::DisableForROS(stream_id sensor_id) { - auto it = _servers.find(sensor_id); +void PrimaryCommands::DisableForROS(carla::streaming::detail::stream_actor_id_type stream_actor_id) { + auto it = _servers.find(stream_actor_id.stream_id); if (it != _servers.end()) { - SendDisableForROS(sensor_id); + SendDisableForROS(stream_actor_id); } } -bool PrimaryCommands::IsEnabledForROS(stream_id sensor_id) { - auto it = _servers.find(sensor_id); +bool PrimaryCommands::IsEnabledForROS(carla::streaming::detail::stream_actor_id_type stream_actor_id) { + auto it = _servers.find(stream_actor_id.stream_id); if (it != _servers.end()) { - return SendIsEnabledForROS(sensor_id); + return SendIsEnabledForROS(stream_actor_id); } return false; } diff --git a/LibCarla/source/carla/multigpu/primaryCommands.h b/LibCarla/source/carla/multigpu/primaryCommands.h index 475f8354f7d..69dc8f9ce06 100644 --- a/LibCarla/source/carla/multigpu/primaryCommands.h +++ b/LibCarla/source/carla/multigpu/primaryCommands.h @@ -9,7 +9,7 @@ // #include "carla/Logging.h" #include "carla/multigpu/commands.h" #include "carla/multigpu/primary.h" -#include "carla/streaming/detail/tcp/Message.h" +#include "carla/streaming/detail/Message.h" #include "carla/streaming/detail/Token.h" #include "carla/streaming/detail/Types.h" @@ -43,21 +43,21 @@ class PrimaryCommands { token_type GetToken(stream_id sensor_id); - void EnableForROS(stream_id sensor_id); + void EnableForROS(carla::streaming::detail::stream_actor_id_type stream_actor_id); - void DisableForROS(stream_id sensor_id); + void DisableForROS(carla::streaming::detail::stream_actor_id_type stream_actor_id); - bool IsEnabledForROS(stream_id sensor_id); + bool IsEnabledForROS(carla::streaming::detail::stream_actor_id_type stream_actor_id); private: // send to one secondary to get the token of a sensor - token_type SendGetToken(carla::streaming::detail::stream_id_type sensor_id); + token_type SendGetToken(carla::streaming::detail::stream_id_type stream_id); // manage ROS enable/disable of sensor - void SendEnableForROS(stream_id sensor_id); - void SendDisableForROS(stream_id sensor_id); - bool SendIsEnabledForROS(stream_id sensor_id); + void SendEnableForROS(carla::streaming::detail::stream_actor_id_type stream_actor_id); + void SendDisableForROS(carla::streaming::detail::stream_actor_id_type stream_actor_id); + bool SendIsEnabledForROS(carla::streaming::detail::stream_actor_id_type stream_actor_id); std::shared_ptr _router; diff --git a/LibCarla/source/carla/multigpu/router.h b/LibCarla/source/carla/multigpu/router.h index c88a799c446..43bb835e39b 100644 --- a/LibCarla/source/carla/multigpu/router.h +++ b/LibCarla/source/carla/multigpu/router.h @@ -7,7 +7,7 @@ #pragma once // #include "carla/Logging.h" -#include "carla/streaming/detail/tcp/Message.h" +#include "carla/streaming/detail/Message.h" #include "carla/ThreadPool.h" #include "carla/multigpu/primary.h" #include "carla/multigpu/primaryCommands.h" diff --git a/LibCarla/source/carla/multigpu/secondary.cpp b/LibCarla/source/carla/multigpu/secondary.cpp index 6fe8cd5da8e..2b697c7adee 100644 --- a/LibCarla/source/carla/multigpu/secondary.cpp +++ b/LibCarla/source/carla/multigpu/secondary.cpp @@ -131,7 +131,7 @@ namespace multigpu { _pool.AsyncRun(worker_threads); } - void Secondary::Write(std::shared_ptr message) { + void Secondary::Write(std::shared_ptr message) { DEBUG_ASSERT(message != nullptr); DEBUG_ASSERT(!message->empty()); std::weak_ptr weak = shared_from_this(); diff --git a/LibCarla/source/carla/multigpu/secondary.h b/LibCarla/source/carla/multigpu/secondary.h index f87160568a5..e697365bbcf 100644 --- a/LibCarla/source/carla/multigpu/secondary.h +++ b/LibCarla/source/carla/multigpu/secondary.h @@ -11,7 +11,7 @@ #include "carla/TypeTraits.h" #include "carla/profiler/LifetimeProfiled.h" #include "carla/multigpu/secondaryCommands.h" -#include "carla/streaming/detail/tcp/Message.h" +#include "carla/streaming/detail/Message.h" #include "carla/streaming/detail/Token.h" #include "carla/streaming/detail/Types.h" #include "carla/ThreadPool.h" @@ -50,7 +50,7 @@ namespace multigpu { void AsyncRun(size_t worker_threads); - void Write(std::shared_ptr message); + void Write(std::shared_ptr message); void Write(Buffer buffer); void Write(std::string text); @@ -63,7 +63,7 @@ namespace multigpu { static_assert( are_same::value, "This function only accepts arguments of type BufferView."); - return std::make_shared(buffers...); + return std::make_shared(buffers...); } private: diff --git a/LibCarla/source/carla/multigpu/secondaryCommands.cpp b/LibCarla/source/carla/multigpu/secondaryCommands.cpp index c234a3e45ec..e5a6243c95a 100644 --- a/LibCarla/source/carla/multigpu/secondaryCommands.cpp +++ b/LibCarla/source/carla/multigpu/secondaryCommands.cpp @@ -6,7 +6,7 @@ // #include "carla/Logging.h" #include "carla/multigpu/secondaryCommands.h" -// #include "carla/streaming/detail/tcp/Message.h" +// #include "carla/streaming/detail/Message.h" namespace carla { namespace multigpu { diff --git a/LibCarla/source/carla/nav/WalkerManager.cpp b/LibCarla/source/carla/nav/WalkerManager.cpp index 0abe7f106f9..1c0d4d5d51d 100644 --- a/LibCarla/source/carla/nav/WalkerManager.cpp +++ b/LibCarla/source/carla/nav/WalkerManager.cpp @@ -8,6 +8,7 @@ #include "carla/Logging.h" #include "carla/client/ActorSnapshot.h" +#include "carla/client/ActorList.h" #include "carla/client/Waypoint.h" #include "carla/client/World.h" #include "carla/client/detail/Simulator.h" @@ -282,18 +283,18 @@ namespace nav { carla::client::World world = _simulator.lock()->GetWorld(); _traffic_lights.clear(); - std::vector actors = _simulator.lock()->GetAllTheActorsInTheEpisode(); - for (auto actor : actors) { - carla::client::ActorSnapshot snapshot = _simulator.lock()->GetActorSnapshot(actor.id); + auto actors = world.GetActors(); + for (auto const &actor : *actors) { // check traffic lights only - if (actor.description.id == "traffic.traffic_light") { + if (actor->GetTypeId() == "traffic.traffic_light") { // get the TL actor - SharedPtr tl = - boost::static_pointer_cast(world.GetActor(actor.id)); - // get the waypoints where the TL affects - std::vector> list = tl->GetStopWaypoints(); - for (auto &way : list) { - _traffic_lights.emplace_back(tl, way->GetTransform().location); + auto tl = boost::dynamic_pointer_cast(actor); + if ( tl != nullptr ) { + // get the waypoints where the TL affects + std::vector> list = tl->GetStopWaypoints(); + for (auto const &way : list) { + _traffic_lights.emplace_back(tl, way->GetTransform().location); + } } } } diff --git a/LibCarla/source/carla/road/Map.cpp b/LibCarla/source/carla/road/Map.cpp index f86ca38a8c1..23c9212b5ce 100644 --- a/LibCarla/source/carla/road/Map.cpp +++ b/LibCarla/source/carla/road/Map.cpp @@ -1161,10 +1161,10 @@ namespace road { next_waypoint = next.front(); geom::Transform next_transform = ComputeTransform(next_waypoint); - double angle = geom::Math::GetVectorAngle( + double abs_angle = geom::Math::GetVectorAngleAbs( current_transform.GetForwardVector(), next_transform.GetForwardVector()); - if (std::abs(angle) > angle_threshold || + if (abs_angle > angle_threshold || std::abs(current_waypoint.s - next_waypoint.s) > max_segment_length) { AddElementToRtree( rtree_elements, diff --git a/LibCarla/source/carla/road/element/LaneCrossingCalculator.cpp b/LibCarla/source/carla/road/element/LaneCrossingCalculator.cpp index e4eeed61652..02391301fbd 100644 --- a/LibCarla/source/carla/road/element/LaneCrossingCalculator.cpp +++ b/LibCarla/source/carla/road/element/LaneCrossingCalculator.cpp @@ -92,7 +92,7 @@ namespace element { const auto transform = map.ComputeTransform(*w0); geom::Vector3D orig_vec = transform.GetForwardVector(); - geom::Vector3D dest_vec = (destination - origin).MakeSafeUnitVector(2 * std::numeric_limits::epsilon()); + geom::Vector3D dest_vec = (destination - origin).MakeUnitVector(2 * std::numeric_limits::epsilon()); // cross product const auto dest_is_at_right = diff --git a/LibCarla/source/carla/ros2/ROS2.cpp b/LibCarla/source/carla/ros2/ROS2.cpp index b4dd6d3df54..b0cb8fca609 100644 --- a/LibCarla/source/carla/ros2/ROS2.cpp +++ b/LibCarla/source/carla/ros2/ROS2.cpp @@ -9,446 +9,481 @@ #include "carla/Logging.h" #include "carla/geom/GeoLocation.h" #include "carla/geom/Vector3D.h" +#include "carla/ros2/ROS2NameRegistry.h" +#include "carla/ros2/ROS2Session.h" +#include "carla/sensor/SensorRegistry.h" #include "carla/sensor/data/DVSEvent.h" +#include "carla/sensor/data/Image.h" #include "carla/sensor/data/LidarData.h" -#include "carla/sensor/data/SemanticLidarData.h" #include "carla/sensor/data/RadarData.h" -#include "carla/sensor/data/Image.h" -#include "carla/sensor/s11n/ImageSerializer.h" +#include "carla/sensor/data/SemanticLidarData.h" #include "carla/sensor/s11n/SensorHeaderSerializer.h" -#include "publishers/CarlaCameraPublisher.h" -#include "publishers/CarlaClockPublisher.h" -#include "publishers/CarlaCollisionPublisher.h" -#include "publishers/CarlaDepthCameraPublisher.h" -#include "publishers/CarlaDVSPublisher.h" -#include "publishers/CarlaGNSSPublisher.h" -#include "publishers/CarlaIMUPublisher.h" -#include "publishers/CarlaISCameraPublisher.h" -#include "publishers/CarlaLidarPublisher.h" -#include "publishers/CarlaNormalsCameraPublisher.h" -#include "publishers/CarlaOpticalFlowCameraPublisher.h" -#include "publishers/CarlaRadarPublisher.h" -#include "publishers/CarlaRGBCameraPublisher.h" -#include "publishers/CarlaSemanticLidarPublisher.h" -#include "publishers/CarlaSSCameraPublisher.h" -#include "publishers/CarlaTransformPublisher.h" - -#include "subscribers/AckermannControlSubscriber.h" -#include "subscribers/CarlaEgoVehicleControlSubscriber.h" +#include "carla/ros2/publishers/CarlaActorListPublisher.h" +#include "carla/ros2/publishers/TransformPublisher.h" +#include "carla/ros2/publishers/UeCollisionPublisher.h" +#include "carla/ros2/publishers/UeDVSCameraPublisher.h" +#include "carla/ros2/publishers/UeDepthCameraPublisher.h" +#include "carla/ros2/publishers/UeGNSSPublisher.h" +#include "carla/ros2/publishers/UeIMUPublisher.h" +#include "carla/ros2/publishers/UeISCameraPublisher.h" +#include "carla/ros2/publishers/UeLidarPublisher.h" +#include "carla/ros2/publishers/UeNormalsCameraPublisher.h" +#include "carla/ros2/publishers/UeOpticalFlowCameraPublisher.h" +#include "carla/ros2/publishers/UeRGBCameraPublisher.h" +#include "carla/ros2/publishers/UeRadarPublisher.h" +#include "carla/ros2/publishers/UeSSCameraPublisher.h" +#include "carla/ros2/publishers/UeSemanticLidarPublisher.h" +#include "carla/ros2/publishers/UeWorldPublisher.h" +#include "carla/ros2/publishers/UeV2XPublisher.h" +#include "carla/ros2/publishers/UeV2XCustomPublisher.h" +#include "carla/ros2/publishers/VehiclePublisher.h" + +#include "carla/ros2/services/DestroyObjectService.h" +#include "carla/ros2/services/GetAvailableMapsService.h" +#include "carla/ros2/services/GetBlueprintsService.h" +#include "carla/ros2/services/LoadMapService.h" +#include "carla/ros2/services/SetEpisodeSettingsService.h" +#include "carla/ros2/services/SpawnObjectService.h" + +#include "carla/ros2/subscribers/AckermannControlSubscriber.h" +#include "carla/ros2/subscribers/VehicleControlSubscriber.h" + +#include "carla/ros2/types/Acceleration.h" +#include "carla/ros2/types/AngularVelocity.h" +#include "carla/ros2/types/Quaternion.h" +#include "carla/ros2/types/Speed.h" +#include "carla/ros2/types/VehicleAckermannControl.h" +#include "carla/ros2/types/VehicleControl.h" #include namespace carla { namespace ros2 { -// static fields -std::shared_ptr ROS2::_instance; - -// list of sensors (should be equal to the list of SensorsRegistry -enum ESensors { - CollisionSensor, - DepthCamera, - NormalsCamera, - DVSCamera, - GnssSensor, - InertialMeasurementUnit, - LaneInvasionSensor, - ObstacleDetectionSensor, - OpticalFlowCamera, - Radar, - RayCastSemanticLidar, - RayCastLidar, - RssSensor, - SceneCaptureCamera, - SemanticSegmentationCamera, - InstanceSegmentationCamera, - WorldObserver, - CameraGBufferUint8, - CameraGBufferFloat, - HSSLidar -}; - -void ROS2::Enable(bool enable) { - _clock_publisher = std::make_shared(); - - _enabled = enable; -} - -void ROS2::SetFrame(uint64_t frame) { - _frame = frame; - - for (auto& element : _subscribers) { - auto actor = element.first; - auto subscriber = element.second; - auto callback = _actor_callbacks.find(actor)->second; - - subscriber->ProcessMessages(callback); +// singleton handling +std::shared_ptr ROS2::GetInstance() { + static std::shared_ptr _instance{nullptr}; + if (_instance == nullptr) { + _instance = std::shared_ptr(new ROS2()); } + return _instance; } -void ROS2::SetTimestamp(double timestamp) { - double integral; - const double fractional = modf(timestamp, &integral); - const double multiplier = 1000000000.0; - _seconds = static_cast(integral); - _nanoseconds = static_cast(fractional * multiplier); - - _clock_publisher->Write(_seconds, _nanoseconds); - _clock_publisher->Publish(); +void ROS2::Enable(carla::rpc::RpcServerInterface *carla_server, + carla::streaming::detail::stream_id_type const world_observer_stream_id, + TopicVisibilityDefaultMode topic_visibility_default_mode) { + _enabled = true; + _topic_visibility_default_mode = topic_visibility_default_mode; + _carla_server = carla_server; + _name_registry = std::make_shared(); + _dispatcher = _carla_server->GetDispatcher(); + _domain_participant_impl = std::make_shared(); + // take basic actor role definition as this is acting as naming parent of others with /carla/world + auto world_observer_actor_definition = carla::ros2::types::ActorNameDefinition::CreateFromRoleName("/", true); + _world_observer_sensor_actor_definition = std::make_shared( + *world_observer_actor_definition, + carla::ros2::types::PublisherSensorType::WorldObserver, + world_observer_stream_id); + log_warning("ROS2 enabled"); } -void ROS2::RegisterActor(void *actor, std::string ros_name, std::string frame_id, bool publish_tf) { - _registered_actors.insert({actor, ros_name}); - _frame_ids.insert({actor, frame_id}); - _tfs.insert({actor, publish_tf}); -} +void ROS2::NotifyInitGame() { + log_warning("ROS2 NotifyInitGame"); -void ROS2::UnregisterActor(void *actor) { - _registered_actors.erase(actor); - _frame_ids.erase(actor); - _actor_parent_map.erase(actor); - _tfs.erase(actor); -} + _carla_sensor_actor_list_publisher = std::make_shared("sensor_list"); + _carla_sensor_actor_list_publisher->Init(_domain_participant_impl); -void ROS2::RegisterActorParent(void *actor, void *parent) { - _actor_parent_map.insert({actor, parent}); + // The world is crucial and has to be instanciated immediately + if (AddSensorUe(_world_observer_sensor_actor_definition)) { + ProcessDataFromUeSensorPreAction(); + } + if (_world_publisher != nullptr) { + _transform_publisher = _world_publisher->GetTransformPublisher(); + } } -void ROS2::RegisterSensor(void *actor, std::string ros_name, std::string frame_id, bool publish_tf) { - RegisterActor(actor, ros_name, frame_id, publish_tf); +void ROS2::NotifyBeginEpisode() { + log_warning("ROS2 NotifyBeginEpisode"); + + auto spawn_object_service = std::make_shared( + *_carla_server, carla::ros2::types::ActorNameDefinition::CreateFromRoleName("spawn_object")); + spawn_object_service->Init(_domain_participant_impl); + _services.push_back(spawn_object_service); + + auto destroy_object_service = std::make_shared( + *_carla_server, carla::ros2::types::ActorNameDefinition::CreateFromRoleName("destroy_object")); + destroy_object_service->Init(_domain_participant_impl); + _services.push_back(destroy_object_service); + + auto get_blueprints_service = std::make_shared( + *_carla_server, carla::ros2::types::ActorNameDefinition::CreateFromRoleName("get_blueprints")); + get_blueprints_service->Init(_domain_participant_impl); + _services.push_back(get_blueprints_service); + + auto get_available_maps_service = std::make_shared( + *_carla_server, carla::ros2::types::ActorNameDefinition::CreateFromRoleName("get_available_maps")); + get_available_maps_service->Init(_domain_participant_impl); + _services.push_back(get_available_maps_service); + + auto load_map_service = std::make_shared( + *_carla_server, carla::ros2::types::ActorNameDefinition::CreateFromRoleName("load_map")); + load_map_service->Init(_domain_participant_impl); + _services.push_back(load_map_service); + + auto set_epsisode_settings_service = std::make_shared( + *_carla_server, carla::ros2::types::ActorNameDefinition::CreateFromRoleName("set_episode_settings")); + set_epsisode_settings_service->Init(_domain_participant_impl); + _services.push_back(set_epsisode_settings_service); } -void ROS2::UnregisterSensor(void *actor) { - UnregisterActor(actor); - _publishers.erase(actor); +void ROS2::NotifyEndEpisode() { + log_warning("ROS2 NotifyEndEpisode"); + _services.clear(); + _ue_sensors.clear(); + _name_registry->Clear(); } -void ROS2::RegisterVehicle(void *actor, std::string ros_name, std::string frame_id, ActorCallback callback) { - RegisterActor(actor, ros_name, frame_id); - - // Register actor callback - _actor_callbacks.insert({actor, std::move(callback)}); - - // Register subscribers - auto base_topic_name = GetActorBaseTopicName(actor); - - auto _vehicle_control_subscriber = std::make_shared(actor, base_topic_name, frame_id); - _subscribers.insert({actor, _vehicle_control_subscriber}); - - auto _ackermann_control_subscriber = std::make_shared(actor, base_topic_name, frame_id); - _subscribers.insert({actor, _ackermann_control_subscriber}); - +void ROS2::NotifyEndGame() { + log_warning("ROS2 NotifyEndGame"); + NotifyEndEpisode(); + _world_publisher.reset(); + _transform_publisher.reset(); + _carla_sensor_actor_list_publisher.reset(); } -void ROS2::UnregisterVehicle(void *actor) { - UnregisterActor(actor); - _actor_callbacks.erase(actor); - _subscribers.erase(actor); +void ROS2::Disable() { + NotifyEndEpisode(); + NotifyEndGame(); + _carla_sensor_actor_list_publisher.reset(); + _world_observer_sensor_actor_definition.reset(); + _dispatcher.reset(); + _domain_participant_impl.reset(); + _name_registry.reset(); + _enabled = false; + log_warning("ROS2 disabled"); } -std::string ROS2::GetActorRosName(void *actor) { - auto it = _registered_actors.find(actor); - return it != _registered_actors.end() ? it->second : ""; +void ROS2::AddVehicleUe(std::shared_ptr vehicle_actor_definition, + carla::ros2::types::VehicleControlCallback vehicle_control_callback, + carla::ros2::types::VehicleAckermannControlCallback vehicle_ackermann_control_callback, + carla::ros2::types::ActorSetTransformCallback vehicle_set_transform_callback) { + log_warning("ROS2::AddVehicleUe(", std::to_string(*vehicle_actor_definition), ")"); + _world_publisher->AddVehicleUe(vehicle_actor_definition, vehicle_control_callback, + vehicle_ackermann_control_callback, vehicle_set_transform_callback); } -std::string ROS2::GetActorBaseTopicName(void *actor) { - auto it = _actor_parent_map.find(actor); - if (it != _actor_parent_map.end()) { - return GetActorBaseTopicName(it->second) + "/" + GetActorRosName(actor); - } else { - return "rt/carla/" + GetActorRosName(actor); - } +void ROS2::AddWalkerUe(std::shared_ptr walker_actor_definition, + carla::ros2::types::WalkerControlCallback walker_control_callback) { + log_warning("ROS2::AddWalkerUe(", std::to_string(*walker_actor_definition), ")"); + _world_publisher->AddWalkerUe(walker_actor_definition, walker_control_callback); } -std::string ROS2::GetFrameId(void *actor) { - auto it = _frame_ids.find(actor); - return it != _frame_ids.end() ? it->second : ""; +void ROS2::AddTrafficLightUe( + std::shared_ptr traffic_light_actor_definition) { + log_warning("ROS2::AddTrafficLightUe(", std::to_string(*traffic_light_actor_definition), ")"); + _world_publisher->AddTrafficLightUe(traffic_light_actor_definition); } -std::string ROS2::GetParentFrameId(void *actor) { - auto it = _actor_parent_map.find(actor); - if (it != _actor_parent_map.end()) { - return GetFrameId(it->second); - } else { - return "map"; - } +void ROS2::AddTrafficSignUe( + std::shared_ptr traffic_sign_actor_definition) { + log_warning("ROS2::AddTrafficSignUe(", std::to_string(*traffic_sign_actor_definition), ")"); + _world_publisher->AddTrafficSignUe(traffic_sign_actor_definition); } -std::shared_ptr ROS2::GetOrCreateTransformPublisher(void *actor) { - - auto it = _tfs.find(actor); - if (it == _tfs.end() || it->second == false) { +ROS2::UeSensor* ROS2::AddSensorUeInternal(std::shared_ptr sensor_actor_definition) { + auto insert_result = _ue_sensors.insert({sensor_actor_definition->stream_id, UeSensor(sensor_actor_definition)}); + if (!insert_result.second) { + log_warning("ROS2::AddSensorUe(", std::to_string(*sensor_actor_definition), + "): Sensor already_registered. Ignoring"); return nullptr; } + _ue_sensors_changed = true; + return &insert_result.first->second; +} - // Check if the transform publisher is already created - auto itp = _tf_publishers.find(actor); - if (itp != _tf_publishers.end()) { - return itp->second; - } - - auto tf_publisher = std::make_shared(); - _tf_publishers.insert({actor, tf_publisher}); - return tf_publisher; +bool ROS2::AddSensorUe(std::shared_ptr sensor_actor_definition) { + auto ue_sensor = AddSensorUeInternal(sensor_actor_definition); + return ue_sensor != nullptr; } -std::shared_ptr ROS2::GetOrCreateSensor(int type, void* actor) { - - // Check if the sensor publisher is already created - auto it = _publishers.find(actor); - if (it != _publishers.end()) { - return it->second; +bool ROS2::AddV2XCustomSensorUe(std::shared_ptr sensor_actor_definition, + carla::ros2::types::V2XCustomSendCallback v2x_custom_send_callback) { + auto ue_sensor = AddSensorUeInternal(sensor_actor_definition); + if ( ue_sensor != nullptr ) { + ue_sensor->v2x_custom_send_callback = v2x_custom_send_callback; + return true; } + return false; +} - auto create_and_register = [&](auto publisher) { - _publishers.insert({actor, publisher}); - return publisher; - }; - - std::string topic_name = GetActorBaseTopicName(actor); - std::string frame_id = GetFrameId(actor); - - switch(type) { - case ESensors::CollisionSensor: - return create_and_register(std::make_shared(topic_name, frame_id)); - case ESensors::DepthCamera: - return create_and_register(std::make_shared(topic_name, frame_id)); - case ESensors::NormalsCamera: - return create_and_register(std::make_shared(topic_name, frame_id)); - case ESensors::DVSCamera: - return create_and_register(std::make_shared(topic_name, frame_id)); - case ESensors::GnssSensor: - return create_and_register(std::make_shared(topic_name, frame_id)); - case ESensors::InertialMeasurementUnit: - return create_and_register(std::make_shared(topic_name, frame_id)); - case ESensors::OpticalFlowCamera: - return create_and_register(std::make_shared(topic_name, frame_id)); - case ESensors::Radar: - return create_and_register(std::make_shared(topic_name, frame_id)); - case ESensors::RayCastSemanticLidar: - return create_and_register(std::make_shared(topic_name, frame_id)); - case ESensors::RayCastLidar: - return create_and_register(std::make_shared(topic_name, frame_id)); - case ESensors::SceneCaptureCamera: - return create_and_register(std::make_shared(topic_name, frame_id)); - case ESensors::SemanticSegmentationCamera: - return create_and_register(std::make_shared(topic_name, frame_id)); - case ESensors::InstanceSegmentationCamera: - return create_and_register(std::make_shared(topic_name, frame_id)); - case ESensors::LaneInvasionSensor: - case ESensors::ObstacleDetectionSensor: - case ESensors::RssSensor: - case ESensors::WorldObserver: - case ESensors::CameraGBufferUint8: - case ESensors::CameraGBufferFloat: - return nullptr; - case ESensors::HSSLidar: - return create_and_register(std::make_shared(topic_name, frame_id)); +void ROS2::AttachActors(ActorId const child, ActorId const parent) { + log_warning("ROS2::AttachActors[", child, "]: parent=", parent); + _name_registry->AttachActors(child, parent); + for (auto iter = _ue_sensors.begin(); iter != _ue_sensors.end(); ++iter) { + if (iter->second.sensor_actor_definition->id == child) { + UeSensor &sensor = iter->second; + if (sensor.publisher) { + log_error("ROS2::AttachActors[", std::to_string(*sensor.sensor_actor_definition), + "]: Sensor attached to parent ", parent, + ". Sensor has already a running publisher with base topic name ", sensor.publisher->get_topic_name(), + " has to be destroyed due to re-attachment"); + sensor.publisher.reset(); + } + _ue_sensors_changed = true; + break; + } } } -void ROS2::ProcessDataFromCamera( - uint64_t sensor_type, - const carla::geom::Transform sensor_transform, - const carla::SharedBufferView buffer, - void *actor) { - - auto base_publisher = GetOrCreateSensor(sensor_type, actor); - auto sensor_publisher = std::dynamic_pointer_cast(base_publisher); - auto transform_publisher = GetOrCreateTransformPublisher(actor); - - const carla::sensor::s11n::ImageSerializer::ImageHeader *header = - reinterpret_cast(buffer->data()); - if (!header) - return; - - sensor_publisher->WriteCameraInfo(_seconds, _nanoseconds, 0, 0, header->height, header->width, header->fov_angle, true); - sensor_publisher->WriteImage(_seconds, _nanoseconds, header->height, header->width, (const uint8_t*) (buffer->data() + carla::sensor::s11n::ImageSerializer::header_offset)); - sensor_publisher->Publish(); - - if (transform_publisher) { - transform_publisher->Write(_seconds, _nanoseconds, GetParentFrameId(actor), GetFrameId(actor), sensor_transform); - transform_publisher->Publish(); +void ROS2::CreateSensorUePublisher(UeSensor &sensor) { + // Create the respective sensor publisher + switch (sensor.sensor_actor_definition->sensor_type) { + case types::PublisherSensorType::CollisionSensor: { + sensor.publisher = std::static_pointer_cast( + std::make_shared(sensor.sensor_actor_definition, _transform_publisher)); + } break; + case types::PublisherSensorType::DepthCamera: { + sensor.publisher = std::static_pointer_cast( + std::make_shared(sensor.sensor_actor_definition, _transform_publisher)); + } break; + case types::PublisherSensorType::NormalsCamera: { + sensor.publisher = std::static_pointer_cast( + std::make_shared(sensor.sensor_actor_definition, _transform_publisher)); + } break; + case types::PublisherSensorType::DVSCamera: { + sensor.publisher = std::static_pointer_cast( + std::make_shared(sensor.sensor_actor_definition, _transform_publisher)); + } break; + case types::PublisherSensorType::GnssSensor: { + sensor.publisher = std::static_pointer_cast( + std::make_shared(sensor.sensor_actor_definition, _transform_publisher)); + } break; + case types::PublisherSensorType::InertialMeasurementUnit: { + sensor.publisher = std::static_pointer_cast( + std::make_shared(sensor.sensor_actor_definition, _transform_publisher)); + } break; + case types::PublisherSensorType::OpticalFlowCamera: { + sensor.publisher = std::static_pointer_cast( + std::make_shared(sensor.sensor_actor_definition, _transform_publisher)); + } break; + case types::PublisherSensorType::Radar: { + sensor.publisher = std::static_pointer_cast( + std::make_shared(sensor.sensor_actor_definition, _transform_publisher)); + } break; + case types::PublisherSensorType::RayCastSemanticLidar: { + sensor.publisher = std::static_pointer_cast( + std::make_shared(sensor.sensor_actor_definition, _transform_publisher)); + } break; + case types::PublisherSensorType::RayCastLidar: { + sensor.publisher = std::static_pointer_cast( + std::make_shared(sensor.sensor_actor_definition, _transform_publisher)); + } break; + case types::PublisherSensorType::SceneCaptureCamera: { + sensor.publisher = std::static_pointer_cast( + std::make_shared(sensor.sensor_actor_definition, _transform_publisher)); + } break; + case types::PublisherSensorType::SemanticSegmentationCamera: { + sensor.publisher = std::static_pointer_cast( + std::make_shared(sensor.sensor_actor_definition, _transform_publisher)); + } break; + case types::PublisherSensorType::InstanceSegmentationCamera: { + sensor.publisher = std::static_pointer_cast( + std::make_shared(sensor.sensor_actor_definition, _transform_publisher)); + } break; + case types::PublisherSensorType::WorldObserver: { + _world_publisher = + std::make_shared(*_carla_server, _name_registry, sensor.sensor_actor_definition); + sensor.publisher = std::static_pointer_cast(_world_publisher); + } break; + case types::PublisherSensorType::V2X : { + sensor.publisher = std::static_pointer_cast( + std::make_shared(sensor.sensor_actor_definition, _transform_publisher)); + } break; + case types::PublisherSensorType::V2XCustom : { + sensor.publisher = std::static_pointer_cast( + std::make_shared(sensor.sensor_actor_definition, sensor.v2x_custom_send_callback, _transform_publisher)); + } break; + case types::PublisherSensorType::RssSensor: + // no server side interface to be implemented: maybe move client based implementation from client to the sensor + // folder for those? in each case should be implemented in a form that the actual calcuations are only performed + // if anyone listening to the topic + case types::PublisherSensorType::CameraGBufferUint8: + case types::PublisherSensorType::CameraGBufferFloat: + + + case types::PublisherSensorType::LaneInvasionSensor: + case types::PublisherSensorType::ObstacleDetectionSensor: + default: { + sensor.publisher_expected = false; + log_error("ROS2::CreateSensorUePublisher[", std::to_string(*sensor.sensor_actor_definition), + "]: Not a UE sensor or no publisher implemented yet"); + } + } + if (sensor.publisher != nullptr) { + if (!sensor.publisher->Init(_domain_participant_impl)) { + log_error("ROS2::CreateSensorUePublisher[", std::to_string(*sensor.sensor_actor_definition), + "]: Failed to init publisher"); + } else { + log_warning("ROS2::CreateSensorUePublisher[", std::to_string(*sensor.sensor_actor_definition), + "]: Publisher initialized"); + } } } -void ROS2::ProcessDataFromGNSS( - uint64_t sensor_type, - const carla::geom::Transform sensor_transform, - const carla::geom::GeoLocation &data, - void *actor) { - - auto base_publisher = GetOrCreateSensor(ESensors::GnssSensor, actor); - auto sensor_publisher = std::dynamic_pointer_cast(base_publisher); - auto transform_publisher = GetOrCreateTransformPublisher(actor); - - sensor_publisher->Write(_seconds, _nanoseconds, data); - sensor_publisher->Publish(); - - if (transform_publisher) { - transform_publisher->Write(_seconds, _nanoseconds, GetParentFrameId(actor), GetFrameId(actor), sensor_transform); - transform_publisher->Publish(); +void ROS2::RemoveActor(ActorId const actor) { + for (auto iter = _ue_sensors.begin(); iter != _ue_sensors.end(); /*no update of iter*/) { + if (iter->second.sensor_actor_definition->id == actor) { + log_warning("ROS2::RemoveSensorUe(", std::to_string(*iter->second.sensor_actor_definition), ")"); + iter = _ue_sensors.erase(iter); + _ue_sensors_changed = true; + } else { + ++iter; + } } + _world_publisher->RemoveActor(actor); } -void ROS2::ProcessDataFromIMU( - uint64_t sensor_type, - const carla::geom::Transform sensor_transform, - carla::geom::Vector3D accelerometer, - carla::geom::Vector3D gyroscope, - float compass, - void *actor) { - - auto base_publisher = GetOrCreateSensor(ESensors::InertialMeasurementUnit, actor); - auto sensor_publisher = std::dynamic_pointer_cast(base_publisher); - auto transform_publisher = GetOrCreateTransformPublisher(actor); - - sensor_publisher->Write(_seconds, _nanoseconds, accelerometer, gyroscope, compass); - sensor_publisher->Publish(); - - if (transform_publisher) { - transform_publisher->Write(_seconds, _nanoseconds, GetParentFrameId(actor), GetFrameId(actor), sensor_transform); - transform_publisher->Publish(); +void ROS2::ProcessMessages() { + for (auto service : _services) { + service->CheckRequest(); } + _world_publisher->ProcessMessages(); } -void ROS2::ProcessDataFromDVS( - uint64_t sensor_type, - const carla::geom::Transform sensor_transform, - const carla::SharedBufferView buffer, - void *actor) { - - auto base_publisher = GetOrCreateSensor(ESensors::DVSCamera, actor); - auto sensor_publisher = std::dynamic_pointer_cast(base_publisher); - auto transform_publisher = GetOrCreateTransformPublisher(actor); - - const carla::sensor::s11n::ImageSerializer::ImageHeader *header = - reinterpret_cast(buffer->data()); - if (!header) - return; - - const size_t elements = (buffer->size() - carla::sensor::s11n::ImageSerializer::header_offset) / sizeof(carla::sensor::data::DVSEvent); - const size_t im_width = header->width; - const size_t im_height = header->height; - - sensor_publisher->WriteCameraInfo(_seconds, _nanoseconds, 0, 0, im_height, im_width, header->fov_angle, true); - sensor_publisher->WriteImage(_seconds, _nanoseconds, elements, header->height, header->width, (const uint8_t*) (buffer->data() + carla::sensor::s11n::ImageSerializer::header_offset)); - sensor_publisher->WritePointCloud(_seconds, _nanoseconds, 1, elements, (uint8_t*) (buffer->data() + carla::sensor::s11n::ImageSerializer::header_offset)); - sensor_publisher->Publish(); - - if (transform_publisher) { - transform_publisher->Write(_seconds, _nanoseconds, GetParentFrameId(actor), GetFrameId(actor), sensor_transform); - transform_publisher->Publish(); +void ROS2::ProcessDataFromUeSensorPreAction() { + for (auto &ue_sensor : _ue_sensors) { + if (ue_sensor.second.publisher_expected && (ue_sensor.second.publisher == nullptr)) { + CreateSensorUePublisher(ue_sensor.second); + } + if (ue_sensor.second.publisher != nullptr) { + if (ue_sensor.second.publisher->SubscribersConnected() && ue_sensor.second.session == nullptr) { + ue_sensor.second.session = std::make_shared(ue_sensor.first); + log_warning("ROS2::ProcessDataFromUeSensorPreAction[", std::to_string(*ue_sensor.second.sensor_actor_definition), + "]: Registering session"); + _dispatcher->RegisterSession(ue_sensor.second.session); + } else if (!ue_sensor.second.publisher->SubscribersConnected() && ue_sensor.second.session != nullptr) { + log_warning("ROS2::ProcessDataFromUeSensorPreAction[", std::to_string(*ue_sensor.second.sensor_actor_definition), + "]: Deregistering session"); + _dispatcher->DeregisterSession(ue_sensor.second.session); + ue_sensor.second.session.reset(); + } + } } -} -void ROS2::ProcessDataFromLidar( - uint64_t sensor_type, - const carla::geom::Transform sensor_transform, - carla::sensor::data::LidarData &data, - void *actor) { - - auto base_publisher = GetOrCreateSensor(ESensors::RayCastLidar, actor); - auto sensor_publisher = std::dynamic_pointer_cast(base_publisher); - auto transform_publisher = GetOrCreateTransformPublisher(actor); - - // The lidar returns a flat list of floats rather than structured detection points. - // Each lidar detection consists of 4 floats: x, y, z, and intensity. - // Divide the total number of floats by 4 to get the number of lidar detections. - size_t width = data._points.size() / 4; - size_t height = 1; - sensor_publisher->WritePointCloud(_seconds, _nanoseconds, height, width, (uint8_t*)data._points.data()); - sensor_publisher->Publish(); - - if (transform_publisher) { - transform_publisher->Write(_seconds, _nanoseconds, GetParentFrameId(actor), GetFrameId(actor), sensor_transform); - transform_publisher->Publish(); + for (auto &ue_sensor : _ue_sensors) { + if ( (ue_sensor.second.publisher != nullptr) ) { + ue_sensor.second.publisher->UpdateSensorDataPreAction(); + } } -} -void ROS2::ProcessDataFromSemanticLidar( - uint64_t sensor_type, - const carla::geom::Transform sensor_transform, - carla::sensor::data::SemanticLidarData &data, - void *actor) { - auto base_publisher = GetOrCreateSensor(ESensors::RayCastSemanticLidar, actor); - auto sensor_publisher = std::dynamic_pointer_cast(base_publisher); - auto transform_publisher = GetOrCreateTransformPublisher(actor); + if (_ue_sensors_changed) { + _ue_sensors_changed = false; + carla_msgs::msg::CarlaActorList actor_list; + for (auto &ue_sensor : _ue_sensors) { + actor_list.actors().push_back(ue_sensor.second.sensor_actor_definition->carla_actor_info(_name_registry)); + } + _carla_sensor_actor_list_publisher->UpdateCarlaActorList(actor_list); + _carla_sensor_actor_list_publisher->Publish(); + } - size_t width = data._ser_points.size(); - size_t height = 1; - sensor_publisher->WritePointCloud(_seconds, _nanoseconds, height, width, (uint8_t*)data._ser_points.data()); - sensor_publisher->Publish(); - if (transform_publisher) { - transform_publisher->Write(_seconds, _nanoseconds, GetParentFrameId(actor), GetFrameId(actor), sensor_transform); - transform_publisher->Publish(); - } + _world_publisher->UpdateSensorDataPreAction(); } -void ROS2::ProcessDataFromRadar( - uint64_t sensor_type, - const carla::geom::Transform sensor_transform, - const carla::sensor::data::RadarData &data, - void *actor) { - - auto base_publisher = GetOrCreateSensor(ESensors::Radar, actor); - auto sensor_publisher = std::dynamic_pointer_cast(base_publisher); - auto transform_publisher = GetOrCreateTransformPublisher(actor); - size_t width = data.GetDetectionCount(); - size_t height = 1; - sensor_publisher->WritePointCloud(_seconds, _nanoseconds, height, width, (uint8_t*)data._detections.data()); - sensor_publisher->Publish(); +void ROS2::ProcessDataFromUeSensor(carla::streaming::detail::stream_id_type const stream_id, + std::shared_ptr message) { + auto ue_sensor = _ue_sensors.find(stream_id); + if (ue_sensor != _ue_sensors.end()) { + auto const &sensor_actor_definition = ue_sensor->second.sensor_actor_definition; + + auto buffer_list_view = message->GetBufferViewSequence(); + // currently we only support sensor header + data buffer + DEBUG_ASSERT_EQ(buffer_list_view.size(), 2u); + carla::SharedBufferView sensor_header_view = *buffer_list_view.begin(); + + auto sensor_header = std::shared_ptr( + sensor_header_view, reinterpret_cast( + sensor_header_view.get()->data())); + + if (ue_sensor->second.publisher) { + if ( ue_sensor->second.publisher->is_enabled_for_ros() ) { + auto data_view_iter = buffer_list_view.begin(); + data_view_iter++; + if (data_view_iter != buffer_list_view.end()) { + ue_sensor->second.publisher->UpdateTransform(sensor_header); + ue_sensor->second.publisher->UpdateSensorData(sensor_header, *data_view_iter); + ue_sensor->second.publisher->Publish(); + } + log_info("Sensor Data to ROS data: frame.(", CurrentFrame(), ") stream.", + std::to_string(*sensor_actor_definition), " Processed."); + + } else { + log_info("Sensor Data to ROS data: frame.(", CurrentFrame(), ") stream.", + std::to_string(*sensor_actor_definition), std::to_string(*ue_sensor->second.publisher->_actor_name_definition), " not enabled for ROS. Dropping data."); + } + } else { + log_error("Sensor Data to ROS data: frame.(", CurrentFrame(), ") stream.", + std::to_string(*sensor_actor_definition), " not registered. Dropping data."); + } - if (transform_publisher) { - transform_publisher->Write(_seconds, _nanoseconds, GetParentFrameId(actor), GetFrameId(actor), sensor_transform); - transform_publisher->Publish(); + } else { + log_error("Sensor Data to ROS data: frame.(", CurrentFrame(), ") stream.", std::to_string(stream_id), + " not registered. Dropping data."); } } -void ROS2::ProcessDataFromObstacleDetection( - uint64_t sensor_type, - const carla::geom::Transform sensor_transform, - AActor *first_ctor, - AActor *second_actor, - float distance, - void *actor) { - log_info("Sensor ObstacleDetector to ROS data: frame.", _frame, "sensor.", sensor_type, "distance.", distance); +void ROS2::ProcessDataFromUeSensorPostAction() { + for (auto &ue_sensor : _ue_sensors) { + if ( (ue_sensor.second.publisher != nullptr) ) { + ue_sensor.second.publisher->UpdateSensorDataPostAction(); + } + } + _world_publisher->UpdateSensorDataPostAction(); } -void ROS2::ProcessDataFromCollisionSensor( - uint64_t sensor_type, - const carla::geom::Transform sensor_transform, - uint32_t other_actor, - carla::geom::Vector3D impulse, - void* actor) { - - auto base_publisher = GetOrCreateSensor(ESensors::CollisionSensor, actor); - auto sensor_publisher = std::dynamic_pointer_cast(base_publisher); - auto transform_publisher = GetOrCreateTransformPublisher(actor); - sensor_publisher->Write(_seconds, _nanoseconds, other_actor, impulse); - sensor_publisher->Publish(); +void ROS2::EnableForROS(carla::streaming::detail::stream_actor_id_type stream_actor_id) { + auto ue_sensor = _ue_sensors.find(stream_actor_id.stream_id); + if (ue_sensor != _ue_sensors.end()) { + if ( !ue_sensor->second.publisher->is_enabled_for_ros(stream_actor_id.actor_id) ) { + log_warning("Enable Sensor for ROS: ", + std::to_string(*ue_sensor->second.publisher->_actor_name_definition)); + ue_sensor->second.publisher->enable_for_ros(stream_actor_id.actor_id); + } + } +} - if (transform_publisher) { - transform_publisher->Write(_seconds, _nanoseconds, GetParentFrameId(actor), GetFrameId(actor), sensor_transform); - transform_publisher->Publish(); +void ROS2::DisableForROS(carla::streaming::detail::stream_actor_id_type stream_actor_id) { + auto ue_sensor = _ue_sensors.find(stream_actor_id.stream_id); + if (ue_sensor != _ue_sensors.end()) { + if ( ue_sensor->second.publisher->is_enabled_for_ros(stream_actor_id.actor_id) ) { + log_warning("Disable Sensor for ROS: ", + std::to_string(*ue_sensor->second.publisher->_actor_name_definition)); + ue_sensor->second.publisher->disable_for_ros(stream_actor_id.actor_id); + } } } -void ROS2::Shutdown() { - _publishers.clear(); - _subscribers.clear(); +bool ROS2::IsEnabledForROS(carla::streaming::detail::stream_actor_id_type stream_actor_id) { + auto ue_sensor = _ue_sensors.find(stream_actor_id.stream_id); + if (ue_sensor != _ue_sensors.end()) { + return ue_sensor->second.publisher->is_enabled_for_ros(stream_actor_id.actor_id); + } + return false; +} - _tf_publishers.clear(); - _clock_publisher.reset(); +uint64_t ROS2::CurrentFrame() const { + return (_world_publisher != nullptr) ? _world_publisher->CurrentFrame() : 0u; +} - _enabled = false; +carla::ros2::types::Timestamp const &ROS2::CurrentTimestamp() const { + static carla::ros2::types::Timestamp const dummy; + return (_world_publisher != nullptr) ? _world_publisher->CurrentTimestamp() : dummy; } -} // namespace ros2 -} // namespace carla +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/ROS2.h b/LibCarla/source/carla/ros2/ROS2.h index 20bcce853ac..27b8b0af98f 100644 --- a/LibCarla/source/carla/ros2/ROS2.h +++ b/LibCarla/source/carla/ros2/ROS2.h @@ -6,162 +6,137 @@ #pragma once -#include "carla/Buffer.h" #include "carla/BufferView.h" -#include "carla/geom/Transform.h" -#include "carla/ros2/ROS2CallbackData.h" -#include "carla/streaming/detail/Types.h" - -#include -#include +#include "carla/ros2/ROS2NameRegistry.h" +#include "carla/ros2/ROS2Session.h" +#include "carla/ros2/types/SensorActorDefinition.h" +#include "carla/ros2/types/TrafficLightActorDefinition.h" +#include "carla/ros2/types/TrafficSignActorDefinition.h" +#include "carla/ros2/types/VehicleActorDefinition.h" +#include "carla/ros2/types/WalkerActorDefinition.h" +#include "carla/rpc/RpcServerInterface.h" +#include "carla/streaming/detail/Message.h" + +#include #include -#include +#include -// forward declarations -class AActor; namespace carla { - namespace geom { - class GeoLocation; - class Vector3D; +namespace ros2 { + +class DdsDomainParticipantImpl; +class UePublisherBaseSensor; +class TransformPublisher; +class CarlaActorListPublisher; +class UeWorldPublisher; +class ServiceInterface; + +class ROS2 { +public: + // deleting copy constructor for singleton + ROS2(const ROS2& obj) = delete; + ~ROS2() = default; + + static std::shared_ptr GetInstance(); + + // starting/stopping + enum class TopicVisibilityDefaultMode { + eOn, + eOff + }; + void Enable(carla::rpc::RpcServerInterface* carla_server, + carla::streaming::detail::stream_id_type const world_observer_stream_id, + TopicVisibilityDefaultMode topic_visibility_default_mode); + bool IsEnabled() const { + return _enabled; } - namespace sensor { - namespace data { - struct DVSEvent; - class LidarData; - class SemanticLidarData; - class RadarData; - } + TopicVisibilityDefaultMode VisibilityDefaultMode() const { + return _topic_visibility_default_mode; + } + void NotifyInitGame(); + void NotifyBeginEpisode(); + void NotifyEndEpisode(); + void NotifyEndGame(); + void Disable(); + + void AttachActors(ActorId const child, ActorId const parent); + + void AddVehicleUe(std::shared_ptr vehicle_actor_definition, + carla::ros2::types::VehicleControlCallback vehicle_control_callback, + carla::ros2::types::VehicleAckermannControlCallback vehicle_ackermann_control_callback, + carla::ros2::types::ActorSetTransformCallback vehicle_set_transform_callback); + void AddWalkerUe(std::shared_ptr walker_actor_definition, + carla::ros2::types::WalkerControlCallback walker_control_callback); + void AddTrafficLightUe( + std::shared_ptr traffic_light_actor_definition); + void AddTrafficSignUe(std::shared_ptr traffic_sign_actor_definition); + bool AddSensorUe(std::shared_ptr sensor_actor_definition); + bool AddV2XCustomSensorUe(std::shared_ptr sensor_actor_definition, + carla::ros2::types::V2XCustomSendCallback v2x_custom_send_callback); + + void RemoveActor(ActorId const actor); + + /** + * Implement actions before sensor data processing + */ + void ProcessDataFromUeSensorPreAction(); + void ProcessDataFromUeSensor(carla::streaming::detail::stream_id_type const stream_id, + std::shared_ptr message); + /** + * Implement actions after sensor data processing + */ + void ProcessDataFromUeSensorPostAction(); + + void EnableForROS(carla::streaming::detail::stream_actor_id_type stream_actor_id); + void DisableForROS(carla::streaming::detail::stream_actor_id_type stream_actor_id); + bool IsEnabledForROS(carla::streaming::detail::stream_actor_id_type stream_actor_id); + + /** + * Process incoming messages + */ + void ProcessMessages(); + + uint64_t CurrentFrame() const; + carla::ros2::types::Timestamp const& CurrentTimestamp() const; + + std::shared_ptr GetNameRegistry() { + return _name_registry; } -} -namespace carla { -namespace ros2 { - class BasePublisher; - class BaseSubscriber; - - class CarlaTransformPublisher; - class CarlaClockPublisher; - -class ROS2 -{ - public: - - // deleting copy constructor for singleton - ROS2(const ROS2& obj) = delete; - static std::shared_ptr GetInstance() { - if (!_instance) - _instance = std::shared_ptr(new ROS2); - return _instance; - } - - // General - void Enable(bool enable); - void Shutdown(); - - bool IsEnabled() { return _enabled; } - - void SetFrame(uint64_t frame); - void SetTimestamp(double timestamp); - - std::string GetActorRosName(void *actor); - std::string GetActorBaseTopicName(void *actor); - - std::string GetFrameId(void *actor); - std::string GetParentFrameId(void *actor); - - // Registration - void RegisterActor(void *actor, std::string ros_name, std::string frame_id, bool publish_tf=true); - void UnregisterActor(void *actor); - - void RegisterActorParent(void *actor, void *parent); - - void RegisterSensor(void *actor, std::string ros_name, std::string frame_id, bool publish_tf); - void UnregisterSensor(void *actor); - - void RegisterVehicle(void *actor, std::string ros_name, std::string frame_id, ActorCallback callback); - void UnregisterVehicle(void *actor); - - // Receiving data to publish - void ProcessDataFromCamera( - uint64_t sensor_type, - const carla::geom::Transform sensor_transform, - const carla::SharedBufferView buffer, - void *actor = nullptr); - void ProcessDataFromGNSS( - uint64_t sensor_type, - const carla::geom::Transform sensor_transform, - const carla::geom::GeoLocation &data, - void *actor = nullptr); - void ProcessDataFromIMU( - uint64_t sensor_type, - const carla::geom::Transform sensor_transform, - carla::geom::Vector3D accelerometer, - carla::geom::Vector3D gyroscope, - float compass, - void *actor = nullptr); - void ProcessDataFromDVS( - uint64_t sensor_type, - const carla::geom::Transform sensor_transform, - const carla::SharedBufferView buffer, - void *actor = nullptr); - void ProcessDataFromLidar( - uint64_t sensor_type, - const carla::geom::Transform sensor_transform, - carla::sensor::data::LidarData &data, - void *actor = nullptr); - void ProcessDataFromSemanticLidar( - uint64_t sensor_type, - const carla::geom::Transform sensor_transform, - carla::sensor::data::SemanticLidarData &data, - void *actor = nullptr); - void ProcessDataFromRadar( - uint64_t sensor_type, - const carla::geom::Transform sensor_transform, - const carla::sensor::data::RadarData &data, - void *actor = nullptr); - void ProcessDataFromObstacleDetection( - uint64_t sensor_type, - const carla::geom::Transform sensor_transform, - AActor *first_actor, - AActor *second_actor, - float distance, - void *actor = nullptr); - void ProcessDataFromCollisionSensor( - uint64_t sensor_type, - const carla::geom::Transform sensor_transform, - uint32_t other_actor, - carla::geom::Vector3D impulse, - void* actor); - - private: - std::shared_ptr GetOrCreateTransformPublisher(void *actor); - std::shared_ptr GetOrCreateSensor(int type, void* actor); +private: + bool _enabled{false}; + TopicVisibilityDefaultMode _topic_visibility_default_mode{TopicVisibilityDefaultMode::eOn}; + carla::rpc::RpcServerInterface* _carla_server{nullptr}; + std::shared_ptr _name_registry{nullptr}; + std::shared_ptr _dispatcher; + std::shared_ptr _domain_participant_impl; + std::shared_ptr _world_observer_sensor_actor_definition; + + struct UeSensor { + UeSensor(std::shared_ptr sensor_actor_definition_) + : sensor_actor_definition(sensor_actor_definition_) {} + std::shared_ptr sensor_actor_definition; + carla::ros2::types::V2XCustomSendCallback v2x_custom_send_callback{nullptr}; + bool publisher_expected{true}; + std::shared_ptr publisher; + std::shared_ptr session; + }; + std::unordered_map _ue_sensors; + bool _ue_sensors_changed{false}; + std::shared_ptr _transform_publisher; + + std::shared_ptr _world_publisher; + + std::list> _services; + + std::shared_ptr _carla_sensor_actor_list_publisher; + + UeSensor* AddSensorUeInternal(std::shared_ptr sensor_actor_definition); + void CreateSensorUePublisher(UeSensor& sensor); // sigleton - ROS2() {}; - - static std::shared_ptr _instance; - - bool _enabled { false }; - uint64_t _frame { 0 }; - int32_t _seconds { 0 }; - uint32_t _nanoseconds { 0 }; - - std::shared_ptr _clock_publisher; - - // actor->parent relationship - std::unordered_map _actor_parent_map; - - std::unordered_map _registered_actors; - std::unordered_map _frame_ids; - - std::unordered_map> _publishers; - std::unordered_multimap> _subscribers; - std::unordered_map _actor_callbacks; - - std::unordered_map _tfs; - std::unordered_map> _tf_publishers; + ROS2(){}; }; -} // namespace ros2 -} // namespace carla +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/ROS2CallbackData.h b/LibCarla/source/carla/ros2/ROS2CallbackData.h deleted file mode 100644 index b857b68bce6..00000000000 --- a/LibCarla/source/carla/ros2/ROS2CallbackData.h +++ /dev/null @@ -1,52 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include - -#ifdef _MSC_VER -#pragma warning(push) -#pragma warning(disable:4583) -#pragma warning(disable:4582) -#include -#pragma warning(pop) -#else -#include -#endif - -namespace carla { -namespace ros2 { - - struct VehicleControl - { - float throttle; - float steer; - float brake; - bool hand_brake; - bool reverse; - int32_t gear; - bool manual_gear_shift; - }; - - struct AckermannControl - { - float steer; - float steer_speed; - float speed; - float acceleration; - float jerk; - }; - - using ROS2CallbackData = boost::variant2::variant< - VehicleControl, - AckermannControl - >; - - using ActorCallback = std::function; - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/ROS2NameRecord.cpp b/LibCarla/source/carla/ros2/ROS2NameRecord.cpp new file mode 100644 index 00000000000..ab2f03b0af4 --- /dev/null +++ b/LibCarla/source/carla/ros2/ROS2NameRecord.cpp @@ -0,0 +1,43 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/ros2/ROS2NameRecord.h" + +#include "carla/ros2/ROS2.h" +#include "carla/ros2/types/SensorActorDefinition.h" +#include "carla/ros2/types/TrafficLightActorDefinition.h" +#include "carla/ros2/types/TrafficSignActorDefinition.h" +#include "carla/ros2/types/VehicleActorDefinition.h" +#include "carla/ros2/types/WalkerActorDefinition.h" + +namespace carla { +namespace ros2 { + +ROS2NameRecord::ROS2NameRecord(std::shared_ptr actor_name_definition) + : _actor_name_definition(actor_name_definition) { + ROS2::GetInstance()->GetNameRegistry()->RegisterRecord(this); +} + +ROS2NameRecord::~ROS2NameRecord() { + ROS2::GetInstance()->GetNameRegistry()->UnregisterRecord(this); +} + +std::string ROS2NameRecord::get_topic_name(std::string postfix) const { + auto topic_name = ROS2::GetInstance()->GetNameRegistry()->TopicName(this); + if (!postfix.empty()) { + topic_name += "/" + postfix; + } + return topic_name; +} + +std::string ROS2NameRecord::frame_id() const { + return ROS2::GetInstance()->GetNameRegistry()->FrameId(this); +} + +std::string ROS2NameRecord::parent_frame_id() const { + return ROS2::GetInstance()->GetNameRegistry()->ParentFrameId(this); +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/ROS2NameRecord.h b/LibCarla/source/carla/ros2/ROS2NameRecord.h new file mode 100644 index 00000000000..5d0d9445c14 --- /dev/null +++ b/LibCarla/source/carla/ros2/ROS2NameRecord.h @@ -0,0 +1,39 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include + +#include "carla/ros2/types/ActorNameDefinition.h" + +namespace carla { +namespace ros2 { + +class DdsDomainParticipantImpl; + +/** + * @brief class to manage the most topic/frame handling in the sense of parent/child role_name, duplicates, etc. + */ +class ROS2NameRecord { +public: + ROS2NameRecord(std::shared_ptr actor_name_definition); + ~ROS2NameRecord(); + + ROS2NameRecord(const ROS2NameRecord&) = delete; + ROS2NameRecord& operator=(const ROS2NameRecord&) = delete; + ROS2NameRecord(ROS2NameRecord&&) = default; + ROS2NameRecord& operator=(ROS2NameRecord&&) = default; + + std::string frame_id() const; + + std::string parent_frame_id() const; + + std::string get_topic_name(std::string postfix = "") const; + + std::shared_ptr _actor_name_definition; +}; + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/ROS2NameRegistry.cpp b/LibCarla/source/carla/ros2/ROS2NameRegistry.cpp new file mode 100644 index 00000000000..f46ede27125 --- /dev/null +++ b/LibCarla/source/carla/ros2/ROS2NameRegistry.cpp @@ -0,0 +1,320 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include + +#include "carla/ros2/ROS2NameRecord.h" +#include "carla/ros2/ROS2NameRegistry.h" +#include "carla/ros2/types/SensorActorDefinition.h" +#include "carla/ros2/types/TrafficLightActorDefinition.h" +#include "carla/ros2/types/TrafficSignActorDefinition.h" +#include "carla/ros2/types/VehicleActorDefinition.h" +#include "carla/ros2/types/WalkerActorDefinition.h" + +namespace carla { +namespace ros2 { + +const ROS2NameRegistry::TopicAndFrame g_empty_topic_and_frame; + +void ROS2NameRegistry::Clear() { + std::lock_guard lock(access_mutex); + record_set.clear(); + parent_map.clear(); + topic_and_frame_map.clear(); +} + +void ROS2NameRegistry::RegisterRecord(ROS2NameRecord const* record) { + std::lock_guard lock(access_mutex); + record_set.insert(record); +} + +void ROS2NameRegistry::UnregisterRecord(ROS2NameRecord const* record) { + std::lock_guard lock(access_mutex); + auto const actor_id = record->_actor_name_definition->id; + record_set.erase(record); + + for (auto iter = parent_map.begin(); iter != parent_map.end(); /*no update of iter*/) { + if (iter->first == actor_id) { + // erase this actor from the map + iter = parent_map.erase(iter); + } else if (iter->second == actor_id) { + // if this actor was the parent of another one, erase this dependency + auto const child = iter->first; + iter = parent_map.erase(iter); + // and update child data + UpdateTopicAndFrameLocked(child); + } else { + ++iter; + } + } + + for (auto iter = topic_and_frame_map.begin(); iter != topic_and_frame_map.end(); /*no update of iter*/) { + if (iter->first._record == record) { + iter = topic_and_frame_map.erase(iter); + } else { + ++iter; + } + } +} + +void ROS2NameRegistry::AttachActors(ActorId const child_id, ActorId const parent_id) { + std::lock_guard lock(access_mutex); + log_debug("ROS2NameRegistry::AttachActors[", child_id, "]: parent=", parent_id); + auto insert_result = parent_map.insert({child_id, parent_id}); + if (!insert_result.second) { + // update parent entry + insert_result.first->second = parent_id; + } + // enforce an update the topic and frames of the child + UpdateTopicAndFrameLocked(child_id); +} + +std::string ROS2NameRegistry::TopicPrefix(ActorId const actor_id) { + std::lock_guard lock(access_mutex); + std::string result_topic_name = ""; + for (auto& record : record_set) { + auto const actor_definition = record->_actor_name_definition; + if (actor_definition->id == actor_id) { + auto const topic_name = GetTopicAndFrameLocked(KeyType(record))._topic_name; + if (result_topic_name.empty()) { + result_topic_name = topic_name; + } else { + auto iter_a = result_topic_name.begin(); + auto iter_b = topic_name.begin(); + while (iter_a != result_topic_name.end() && iter_b != topic_name.end() && (*iter_a == *iter_b)) { + iter_a++; + iter_b++; + } + if (iter_a == result_topic_name.end()) { + // result_topic_name is already shortest common prefix + } else if (iter_b == topic_name.end()) { + // topic_name is new shortest common prefix + result_topic_name = topic_name; + } else { + result_topic_name = {result_topic_name.begin(), iter_a}; + } + } + } + } + return result_topic_name; +} + +ROS2NameRegistry::TopicAndFrame const& ROS2NameRegistry::GetTopicAndFrameLocked(ROS2NameRecord const* record) { + return GetTopicAndFrameLocked(KeyType(record)); +} + +ROS2NameRegistry::TopicAndFrame const& ROS2NameRegistry::GetParentTopicAndFrameLocked( + ROS2NameRecord const* child_record) { + ActorId const child_id = child_record->_actor_name_definition->id; + // multiple parent entries are not allowed + auto find_result = parent_map.find(child_id); + if (find_result != parent_map.end()) { + auto const parent_actor_id = find_result->second; + std::map::iterator parent_iter = topic_and_frame_map.end(); + for (auto iter = topic_and_frame_map.begin(); iter != topic_and_frame_map.end(); ++iter) { + if (iter->first._actor_id == parent_actor_id) { + if (parent_iter != topic_and_frame_map.end()) { + log_error("ROS2NameRegistry::GetParentTopicAndFrameLocked: multiple parent candidates for child ", + std::to_string(*child_record->_actor_name_definition), " found. ", " Potential Parents ", + std::to_string(*iter->first._record->_actor_name_definition), + std::to_string(*parent_iter->first._record->_actor_name_definition), + " This is not an expected configuration. Cannot decide. Ignore parent"); + return g_empty_topic_and_frame; + } else { + parent_iter = iter; + } + } + } + if (parent_iter != topic_and_frame_map.end()) { + return parent_iter->second; + } else { + // create the parent topic and frame + ROS2NameRecord const* parent_record = nullptr; + for (auto& record : record_set) { + if (record->_actor_name_definition->id == parent_actor_id) { + if (parent_record != nullptr) { + log_error("ROS2NameRegistry::GetParentTopicAndFrameLocked: multiple parent candidates for child ", + std::to_string(*child_record->_actor_name_definition), " found. ", " Potential Parents ", + std::to_string(*record->_actor_name_definition), + std::to_string(*parent_record->_actor_name_definition), + " This is not an expected configuration. Cannot decide. Ignore parent"); + return g_empty_topic_and_frame; + } else { + parent_record = record; + } + } + } + if (parent_record != nullptr) { + KeyType const key(parent_record); + return CreateTopicAndFrameLocked(key)->second; + } else { + log_error("ROS2NameRegistry::GetParentTopicAndFrameLocked: no parent candidate found for child ", + std::to_string(*child_record->_actor_name_definition), " found. ", + " This is not an expected configuration. Cannot decide. Ignore parent_id=", parent_actor_id); + return g_empty_topic_and_frame; + } + } + } + return g_empty_topic_and_frame; +} + +ROS2NameRegistry::TopicAndFrame const& ROS2NameRegistry::GetTopicAndFrameLocked(ROS2NameRegistry::KeyType const& key) { + auto find_result = topic_and_frame_map.find(key); + if (find_result != topic_and_frame_map.end()) { + return find_result->second; + } else { + return CreateTopicAndFrameLocked(key)->second; + } +} + +void ROS2NameRegistry::UpdateTopicAndFrameLocked(carla::streaming::detail::actor_id_type actor_id) { + // update all of this + for (auto& record : record_set) { + auto const actor_definition = record->_actor_name_definition; + if (actor_definition->id == actor_id) { + KeyType const key(record); + (void)CreateTopicAndFrameLocked(key); + } + } +} + +std::string number_to_three_letter_string(uint32_t number) { + auto number_string = std::to_string(number); + if (number_string.length() < 3u) { + number_string.insert(number_string.begin(), 3u - number_string.length(), '0'); + } + return number_string; +} + +std::map::iterator +ROS2NameRegistry::CreateTopicAndFrameLocked(ROS2NameRegistry::KeyType const& key) { + auto const actor_definition = key._record->_actor_name_definition; + + TopicAndFrame parent_topic_and_frame; + auto parent_iter = parent_map.find(key._actor_id); + if (parent_iter != parent_map.end()) { + // get the data, if not availble, update also the parent + parent_topic_and_frame = GetParentTopicAndFrameLocked(key._record); + } + + ROS2NameRegistry::TopicAndFrame topic_and_frame("rt/carla"); + // first bring in the parent hierarchy if present + if (!parent_topic_and_frame._topic_name.empty()) { + if (parent_topic_and_frame._topic_name.find("rt/carla") == 0) { + topic_and_frame._topic_name = parent_topic_and_frame._topic_name; + } else { + topic_and_frame._topic_name += "/" + parent_topic_and_frame._topic_name; + } + } + if (!parent_topic_and_frame._frame_id.empty()) { + topic_and_frame._frame_id = parent_topic_and_frame._frame_id; + } + + // let us query the type of actor we have + auto vehicle_actor_definition = + std::dynamic_pointer_cast(actor_definition); + auto walker_actor_definition = std::dynamic_pointer_cast(actor_definition); + auto sensor_actor_definition = std::dynamic_pointer_cast(actor_definition); + auto traffic_light_actor_definition = + std::dynamic_pointer_cast(actor_definition); + auto traffic_sign_actor_definition = + std::dynamic_pointer_cast(actor_definition); + + // prefix with generic type prefix + std::string type; + if (vehicle_actor_definition != nullptr) { + type = "vehicles"; + } else if (walker_actor_definition != nullptr) { + type = "walkers"; + } else if (traffic_light_actor_definition != nullptr) { + type = "traffic_lights"; + } else if (traffic_sign_actor_definition != nullptr) { + type = "traffic_signs"; + } else if ((sensor_actor_definition != nullptr)&&(sensor_actor_definition->stream_id!=1)) { + type = "sensors"; + } else { + type = "world"; + } + // add type + topic_and_frame = ExpandTopicName(topic_and_frame, type); + + std::string individual_name; + if (sensor_actor_definition != nullptr) { + // on sensors we use the sensor name as additions type prefix + auto pos = actor_definition->ros_name.find_last_of('.'); + if (pos != std::string::npos) { + topic_and_frame = ExpandTopicName(topic_and_frame, actor_definition->ros_name.substr(pos + 1u)); + } else { + topic_and_frame = ExpandTopicName(topic_and_frame, actor_definition->ros_name); + } + // and use stream id as individualization + auto const stream_id_string = "/stream_" + number_to_three_letter_string(sensor_actor_definition->stream_id); + if (IsTopicNameAvailable(topic_and_frame, stream_id_string)) { + individual_name = stream_id_string; + } + } + + // the role name overrules other individualization + if (!actor_definition->role_name.empty()) { + if (IsTopicNameAvailable(topic_and_frame, actor_definition->role_name)) { + individual_name = actor_definition->role_name; + } + } + // no valid individualization yet, use actor id + if (individual_name.empty()) { + auto const actor_id_string = "actor_" + number_to_three_letter_string(actor_definition->id); + if (IsTopicNameAvailable(topic_and_frame, actor_id_string)) { + individual_name = actor_id_string; + } + } + // if also this doesn't help, we try with a random number using the actor_id as initialization + if (individual_name.empty()) { + std::srand(actor_definition->id); + individual_name = "randomid_" + number_to_three_letter_string(uint32_t(std::rand())); + } + topic_and_frame = ExpandTopicName(topic_and_frame, individual_name); + + auto insert_result = topic_and_frame_map.insert({key, topic_and_frame}); + if (!insert_result.second) { + // enforce update if already there + insert_result.first->second = topic_and_frame; + } + + return insert_result.first; +} + +ROS2NameRegistry::TopicAndFrame ROS2NameRegistry::ExpandTopicName(TopicAndFrame const& topic_and_frame, + std::string const& postfix) { + auto postfix_adapted = postfix; + while (postfix_adapted.front() == '/') { + postfix_adapted.erase(postfix_adapted.begin()); + } + if (postfix_adapted.empty()) { + return topic_and_frame; + } + TopicAndFrame expanded_topic_and_frame = topic_and_frame; + if (expanded_topic_and_frame._frame_id.back() != '/') { + expanded_topic_and_frame._frame_id.push_back('/'); + } + if (expanded_topic_and_frame._frame_id.front() == '/') { + expanded_topic_and_frame._frame_id.erase(0u, 1u); + } + if (expanded_topic_and_frame._topic_name.back() != '/') { + expanded_topic_and_frame._topic_name.push_back('/'); + } + expanded_topic_and_frame._frame_id += postfix_adapted; + expanded_topic_and_frame._topic_name += postfix_adapted; + return expanded_topic_and_frame; +} + +bool ROS2NameRegistry::IsTopicNameAvailable(TopicAndFrame const& topic_and_frame, std::string const& individual_name) { + auto topic_name_check = ExpandTopicName(topic_and_frame, individual_name)._topic_name; + auto iter = + std::find_if(topic_and_frame_map.begin(), topic_and_frame_map.end(), + [topic_name_check](auto const& element) { return element.second._topic_name == topic_name_check; }); + return iter == topic_and_frame_map.end(); +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/ROS2NameRegistry.h b/LibCarla/source/carla/ros2/ROS2NameRegistry.h new file mode 100644 index 00000000000..76c70c5259b --- /dev/null +++ b/LibCarla/source/carla/ros2/ROS2NameRegistry.h @@ -0,0 +1,121 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include +#include +#include + +#include "carla/ros2/ROS2NameRecord.h" + +namespace carla { +namespace ros2 { + +/** + * @brief Registry to manage topic/frame handling in the sense of parent/child role_name, duplicates, etc. + * Calls to this object are thread-safe + */ +class ROS2NameRegistry { +public: + ROS2NameRegistry() = default; + ~ROS2NameRegistry() = default; + + void Clear(); + + // registering and unregistering records + void RegisterRecord(ROS2NameRecord const* record); + void UnregisterRecord(ROS2NameRecord const* record); + + // attaching actors to each other + void AttachActors(carla::streaming::detail::actor_id_type const child, carla::streaming::detail::actor_id_type const parent); + + struct TopicAndFrame { + TopicAndFrame(std::string topic_name = "", std::string frame_id = "") + : _topic_name(topic_name), _frame_id(frame_id) {} + std::string _topic_name = ""; + std::string _frame_id = ""; + }; + + carla::streaming::detail::actor_id_type ParentActorId(carla::streaming::detail::actor_id_type const child_id) const { + std::lock_guard lock(access_mutex); + carla::streaming::detail::actor_id_type parent_actor_id = 0; + auto find_result = parent_map.find(child_id); + if (find_result != parent_map.end()) { + parent_actor_id = find_result->second; + } + return parent_actor_id; + } + + /*! + @brief returns the shortest common prefix of all registered topic names for this actor_id + */ + std::string TopicPrefix(carla::streaming::detail::actor_id_type const actor_id); + + std::string FrameId(ROS2NameRecord const* record) { + std::lock_guard lock(access_mutex); + return GetTopicAndFrameLocked(record)._frame_id; + } + std::string TopicName(ROS2NameRecord const* record) { + std::lock_guard lock(access_mutex); + return GetTopicAndFrameLocked(record)._topic_name; + } + + std::string ParentFrameId(ROS2NameRecord const* record) { + std::lock_guard lock(access_mutex); + auto parent_frame_id = GetParentTopicAndFrameLocked(record)._frame_id; + if (parent_frame_id.empty()) { + parent_frame_id = "map"; + } else if (parent_frame_id.find("rt/carla") == 0) { + // fully qualified parent + return parent_frame_id.substr(8); + } + return parent_frame_id; + } + std::string ParentTopicName(ROS2NameRecord const* record) { + std::lock_guard lock(access_mutex); + return GetParentTopicAndFrameLocked(record)._topic_name; + } + +private: + ROS2NameRegistry(const ROS2NameRegistry&) = delete; + ROS2NameRegistry& operator=(const ROS2NameRegistry&) = delete; + ROS2NameRegistry(ROS2NameRegistry&&) = delete; + ROS2NameRegistry& operator=(ROS2NameRegistry&&) = delete; + + bool IsTopicNameAvailable(TopicAndFrame const& topic_and_frame, std::string const& individual_name); + TopicAndFrame ExpandTopicName(TopicAndFrame const& topic_and_frame, std::string const& postfix); + + struct KeyType { + explicit KeyType(ROS2NameRecord const* record) : _record(record), _actor_id(record->_actor_name_definition->id) {} + + bool operator<(const KeyType& other) const { + if (_actor_id == other._actor_id) { + return _record < other._record; + } else { + return _actor_id < other._actor_id; + } + } + + ROS2NameRecord const* const _record; + carla::streaming::detail::actor_id_type _actor_id; + }; + + // locked operations + TopicAndFrame const& GetTopicAndFrameLocked(ROS2NameRecord const* record); + TopicAndFrame const& GetParentTopicAndFrameLocked(ROS2NameRecord const* record); + + TopicAndFrame const& GetTopicAndFrameLocked(KeyType const& key); + void UpdateTopicAndFrameLocked(carla::streaming::detail::actor_id_type actor_id); + std::map::iterator CreateTopicAndFrameLocked(KeyType const& key); + + mutable std::mutex access_mutex; + std::set record_set; + std::map parent_map; + std::map topic_and_frame_map; +}; + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/ROS2QoS.h b/LibCarla/source/carla/ros2/ROS2QoS.h new file mode 100644 index 00000000000..1a13642ccbd --- /dev/null +++ b/LibCarla/source/carla/ros2/ROS2QoS.h @@ -0,0 +1,74 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include + +namespace carla { +namespace ros2 { + +/* + * Struct providing the most prominent ROS2 ROS2QoS parameters + * Default values are selected to be the default used by the ROS2. + * + * Reliability::RELIABLE + * Durability::VOLATILE + * History::KEEP_LAST, depth: 10u + */ +struct ROS2QoS { + ROS2QoS &keep_last(size_t depth) { + _history = History::KEEP_LAST; + _history_depth = int32_t(depth); + return *this; + } + + ROS2QoS &keep_all() { + _history = History::KEEP_ALL; + return *this; + } + + ROS2QoS &reliable() { + _reliability = Reliability::RELIABLE; + return *this; + } + + ROS2QoS &best_effort() { + _reliability = Reliability::BEST_EFFORT; + return *this; + } + + ROS2QoS &durability_volatile() { + _durability = Durability::VOLATILE; + return *this; + } + + ROS2QoS &transient_local() { + _durability = Durability::TRANSIENT_LOCAL; + return *this; + } + + enum class Reliability { SYSTEM_DEFAULT, BEST_EFFORT, RELIABLE } _reliability; + + enum class Durability { SYSTEM_DEFAULT, TRANSIENT_LOCAL, VOLATILE } _durability; + + enum class History { SYSTEM_DEFAULT, KEEP_LAST, KEEP_ALL } _history; + + int32_t _history_depth; +}; + +static constexpr ROS2QoS DEFAULT_ROS2_QOS{ ROS2QoS::Reliability::RELIABLE, ROS2QoS::Durability::VOLATILE, + ROS2QoS::History::KEEP_LAST, 10}; + +static constexpr ROS2QoS DEFAULT_SENSOR_DATA_QOS{ROS2QoS::Reliability::RELIABLE, ROS2QoS::Durability::VOLATILE, + ROS2QoS::History::KEEP_LAST, 10}; + +static constexpr ROS2QoS DEFAULT_SUBSCRIBER_QOS{ROS2QoS::Reliability::BEST_EFFORT, ROS2QoS::Durability::VOLATILE, + ROS2QoS::History::KEEP_LAST, 10}; + +static constexpr ROS2QoS DEFAULT_PUBLISHER_QOS{ROS2QoS::Reliability::RELIABLE, ROS2QoS::Durability::TRANSIENT_LOCAL, + ROS2QoS::History::KEEP_LAST, 10}; + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/ROS2Session.cpp b/LibCarla/source/carla/ros2/ROS2Session.cpp new file mode 100644 index 00000000000..94d229be24e --- /dev/null +++ b/LibCarla/source/carla/ros2/ROS2Session.cpp @@ -0,0 +1,34 @@ +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/ros2/ROS2Session.h" +#include "carla/ros2/ROS2.h" + +namespace carla { +namespace ros2 { + +/// Writes a message to the ROS2 publisher. +void ROS2Session::WriteMessage(std::shared_ptr message) { + auto ROS2 = carla::ros2::ROS2::GetInstance(); + ROS2->ProcessDataFromUeSensor(_stream_id, message); +} + +void ROS2Session::EnableForROS(carla::streaming::detail::actor_id_type actor_id) { + auto ROS2 = carla::ros2::ROS2::GetInstance(); + ROS2->EnableForROS({_stream_id, actor_id}); +} + +void ROS2Session::DisableForROS(carla::streaming::detail::actor_id_type actor_id) { + auto ROS2 = carla::ros2::ROS2::GetInstance(); + ROS2->DisableForROS({_stream_id, actor_id}); +} + +bool ROS2Session::IsEnabledForROS(carla::streaming::detail::actor_id_type actor_id) { + auto ROS2 = carla::ros2::ROS2::GetInstance(); + return ROS2->IsEnabledForROS({_stream_id, actor_id}); +} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/ROS2Session.h b/LibCarla/source/carla/ros2/ROS2Session.h new file mode 100644 index 00000000000..61e590a5d42 --- /dev/null +++ b/LibCarla/source/carla/ros2/ROS2Session.h @@ -0,0 +1,36 @@ +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/streaming/detail/Session.h" + +namespace carla { +namespace ros2 { + +/// A ROS2 streaming session to be able to (re-)use the standard server tcp buffers to receive the data +// to be published via ROS2 +class ROS2Session : public carla::streaming::detail::Session { +public: + ROS2Session(carla::streaming::detail::stream_id_type stream_id) : carla::streaming::detail::Session(stream_id) {} + + /// Writes a message to the ROS2 publisher. + void WriteMessage(std::shared_ptr message) override; + + /// Post a job to close the session. + virtual void Close() override { + // ROS2 session is closed in case there are no subscribers anymore + // this is handled directly within ROS2 class + // nothing to be done here + } + + void EnableForROS(carla::streaming::detail::actor_id_type actor_id) override; + void DisableForROS(carla::streaming::detail::actor_id_type actor_id)override; + bool IsEnabledForROS(carla::streaming::detail::actor_id_type actor_id) override; +}; + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/fastdds/README.md b/LibCarla/source/carla/ros2/fastdds/README.md new file mode 100644 index 00000000000..2c44c1746aa --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/README.md @@ -0,0 +1,20 @@ +To update the types within this folder one has to: + + + * Checkout the github.com/carla-simulator/ros-carla-msgs repository + ```git clone https://github.com/carla-simulator/ros-carla-msgs``` + * install ROS2 on the system and all message dependencies of the carla_msgs (see ros-carla-msgs docu) + * in case the carla msg files are changed: + - build the ROS2 package of the carla_msgs + - copy the idl files from the build folder into the respective carla_msgs folder + - revert the removal of "#pragma once" line within the overridden idls + - add "#pragma once" directive to newly created idls + * To have all relevant files beeing placed in the correct subfolders by the code generator it is best practice to copy the carla_msgs folder + in parallel to the other folders of your ROS2 system first and execute the generator from the respective ROS2 folder e.g. + ``` + sudo cp -r carla_msgs /opt/ros//share + Fast-DDS-GEN/scripts/fastddsgen -d /output-code -I /opt/ros//share/ -typeros2 carla_msgs/msg/*.idl + ``` + In case you get errors in some of the idl files: add "#pragma once" directive to those idls to ensure they are only included once by the generator. + * In some cases you will have to rename variables because of name clashes within different sub-namespaces which the fastddsgen generator is not able to + distiguish. Easiest workaround for variables is placing a "_" in front of the name, so the output will be the same as expected. On class files append e.g. "BLABLA" and later perform a search and replace. Alternatively wait until the generator is fixed and works properly diff --git a/LibCarla/source/carla/ros2/types/AckermannDrive.cpp b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDrive.cxx similarity index 87% rename from LibCarla/source/carla/ros2/types/AckermannDrive.cpp rename to LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDrive.cxx index 7e8c0871dd3..8688c1a6e49 100644 --- a/LibCarla/source/carla/ros2/types/AckermannDrive.cpp +++ b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDrive.cxx @@ -34,20 +34,17 @@ using namespace eprosima::fastcdr::exception; #include -#define ackermann_msgs_msg_AckermannDrive_max_cdr_typesize 20ULL; -#define ackermann_msgs_msg_AckermannDrive_max_key_cdr_typesize 0ULL; - ackermann_msgs::msg::AckermannDrive::AckermannDrive() { - // float m_steering_angle + // m_steering_angle com.eprosima.idl.parser.typecode.PrimitiveTypeCode@2654635 m_steering_angle = 0.0; - // float m_steering_angle_velocity + // m_steering_angle_velocity com.eprosima.idl.parser.typecode.PrimitiveTypeCode@737a135b m_steering_angle_velocity = 0.0; - // float m_speed + // m_speed com.eprosima.idl.parser.typecode.PrimitiveTypeCode@687ef2e0 m_speed = 0.0; - // float m_acceleration + // m_acceleration com.eprosima.idl.parser.typecode.PrimitiveTypeCode@15dcfae7 m_acceleration = 0.0; - // float m_jerk + // m_jerk com.eprosima.idl.parser.typecode.PrimitiveTypeCode@3da05287 m_jerk = 0.0; } @@ -58,7 +55,6 @@ ackermann_msgs::msg::AckermannDrive::~AckermannDrive() - } ackermann_msgs::msg::AckermannDrive::AckermannDrive( @@ -72,7 +68,7 @@ ackermann_msgs::msg::AckermannDrive::AckermannDrive( } ackermann_msgs::msg::AckermannDrive::AckermannDrive( - AckermannDrive&& x) noexcept + AckermannDrive&& x) { m_steering_angle = x.m_steering_angle; m_steering_angle_velocity = x.m_steering_angle_velocity; @@ -95,7 +91,7 @@ ackermann_msgs::msg::AckermannDrive& ackermann_msgs::msg::AckermannDrive::operat } ackermann_msgs::msg::AckermannDrive& ackermann_msgs::msg::AckermannDrive::operator =( - AckermannDrive&& x) noexcept + AckermannDrive&& x) { m_steering_angle = x.m_steering_angle; @@ -123,8 +119,26 @@ bool ackermann_msgs::msg::AckermannDrive::operator !=( size_t ackermann_msgs::msg::AckermannDrive::getMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return ackermann_msgs_msg_AckermannDrive_max_cdr_typesize; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + + return current_alignment - initial_alignment; } size_t ackermann_msgs::msg::AckermannDrive::getCdrSerializedSize( @@ -318,12 +332,14 @@ float& ackermann_msgs::msg::AckermannDrive::jerk() } - size_t ackermann_msgs::msg::AckermannDrive::getKeyMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return ackermann_msgs_msg_AckermannDrive_max_key_cdr_typesize; + size_t current_align = current_alignment; + + + + return current_align; } bool ackermann_msgs::msg::AckermannDrive::isKeyDefined() @@ -335,7 +351,7 @@ void ackermann_msgs::msg::AckermannDrive::serializeKey( eprosima::fastcdr::Cdr& scdr) const { (void) scdr; + } - diff --git a/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDrive.h b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDrive.h new file mode 100644 index 00000000000..9d0e123cf05 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDrive.h @@ -0,0 +1,264 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AckermannDrive.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVE_H_ +#define _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVE_H_ + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(AckermannDrive_SOURCE) +#define AckermannDrive_DllAPI __declspec(dllexport) +#else +#define AckermannDrive_DllAPI __declspec(dllimport) +#endif // AckermannDrive_SOURCE +#else +#define AckermannDrive_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define AckermannDrive_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace ackermann_msgs { +namespace msg { +/*! + * @brief This class represents the structure AckermannDrive defined by the user in the IDL file. + * @ingroup ACKERMANNDRIVE + */ +class AckermannDrive { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport AckermannDrive(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~AckermannDrive(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object ackermann_msgs::msg::AckermannDrive that will be copied. + */ + eProsima_user_DllExport AckermannDrive(const AckermannDrive& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object ackermann_msgs::msg::AckermannDrive that will be copied. + */ + eProsima_user_DllExport AckermannDrive(AckermannDrive&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object ackermann_msgs::msg::AckermannDrive that will be copied. + */ + eProsima_user_DllExport AckermannDrive& operator=(const AckermannDrive& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object ackermann_msgs::msg::AckermannDrive that will be copied. + */ + eProsima_user_DllExport AckermannDrive& operator=(AckermannDrive&& x); + + /*! + * @brief Comparison operator. + * @param x ackermann_msgs::msg::AckermannDrive object to compare. + */ + eProsima_user_DllExport bool operator==(const AckermannDrive& x) const; + + /*! + * @brief Comparison operator. + * @param x ackermann_msgs::msg::AckermannDrive object to compare. + */ + eProsima_user_DllExport bool operator!=(const AckermannDrive& x) const; + + /*! + * @brief This function sets a value in member steering_angle + * @param _steering_angle New value for member steering_angle + */ + eProsima_user_DllExport void steering_angle(float _steering_angle); + + /*! + * @brief This function returns the value of member steering_angle + * @return Value of member steering_angle + */ + eProsima_user_DllExport float steering_angle() const; + + /*! + * @brief This function returns a reference to member steering_angle + * @return Reference to member steering_angle + */ + eProsima_user_DllExport float& steering_angle(); + + /*! + * @brief This function sets a value in member steering_angle_velocity + * @param _steering_angle_velocity New value for member steering_angle_velocity + */ + eProsima_user_DllExport void steering_angle_velocity(float _steering_angle_velocity); + + /*! + * @brief This function returns the value of member steering_angle_velocity + * @return Value of member steering_angle_velocity + */ + eProsima_user_DllExport float steering_angle_velocity() const; + + /*! + * @brief This function returns a reference to member steering_angle_velocity + * @return Reference to member steering_angle_velocity + */ + eProsima_user_DllExport float& steering_angle_velocity(); + + /*! + * @brief This function sets a value in member speed + * @param _speed New value for member speed + */ + eProsima_user_DllExport void speed(float _speed); + + /*! + * @brief This function returns the value of member speed + * @return Value of member speed + */ + eProsima_user_DllExport float speed() const; + + /*! + * @brief This function returns a reference to member speed + * @return Reference to member speed + */ + eProsima_user_DllExport float& speed(); + + /*! + * @brief This function sets a value in member acceleration + * @param _acceleration New value for member acceleration + */ + eProsima_user_DllExport void acceleration(float _acceleration); + + /*! + * @brief This function returns the value of member acceleration + * @return Value of member acceleration + */ + eProsima_user_DllExport float acceleration() const; + + /*! + * @brief This function returns a reference to member acceleration + * @return Reference to member acceleration + */ + eProsima_user_DllExport float& acceleration(); + + /*! + * @brief This function sets a value in member jerk + * @param _jerk New value for member jerk + */ + eProsima_user_DllExport void jerk(float _jerk); + + /*! + * @brief This function returns the value of member jerk + * @return Value of member jerk + */ + eProsima_user_DllExport float jerk() const; + + /*! + * @brief This function returns a reference to member jerk + * @return Reference to member jerk + */ + eProsima_user_DllExport float& jerk(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const ackermann_msgs::msg::AckermannDrive& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + float m_steering_angle; + float m_steering_angle_velocity; + float m_speed; + float m_acceleration; + float m_jerk; +}; +} // namespace msg +} // namespace ackermann_msgs + +#endif // _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/AckermannDrivePubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDrivePubSubTypes.cxx similarity index 85% rename from LibCarla/source/carla/ros2/types/AckermannDrivePubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDrivePubSubTypes.cxx index 37ff8e081ec..1938057b3ab 100644 --- a/LibCarla/source/carla/ros2/types/AckermannDrivePubSubTypes.cpp +++ b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDrivePubSubTypes.cxx @@ -62,15 +62,15 @@ namespace ackermann_msgs { // Object that serializes the data. eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); try { - // Serialize encapsulation - ser.serialize_encapsulation(); // Serialize the object. p_type->serialize(ser); } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) { return false; } @@ -84,25 +84,25 @@ namespace ackermann_msgs { SerializedPayload_t* payload, void* data) { - try - { - // Convert DATA to pointer of your type - AckermannDrive* p_type = static_cast(data); + //Convert DATA to pointer of your type + AckermannDrive* p_type = static_cast(data); - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); - // Deserialize encapsulation. - deser.read_encapsulation(); - payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + try + { // Deserialize the object. p_type->deserialize(deser); } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) { return false; } @@ -173,6 +173,4 @@ namespace ackermann_msgs { } //End of namespace msg - } //End of namespace ackermann_msgs - diff --git a/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDrivePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDrivePubSubTypes.h new file mode 100644 index 00000000000..24182acab85 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDrivePubSubTypes.h @@ -0,0 +1,91 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AckermannDrivePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVE_PUBSUBTYPES_H_ + +#include +#include + +#include "AckermannDrive.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated AckermannDrive is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace ackermann_msgs { +namespace msg { +/*! + * @brief This class represents the TopicDataType of the type AckermannDrive defined by the user in the IDL file. + * @ingroup ACKERMANNDRIVE + */ +class AckermannDrivePubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef AckermannDrive type; + + eProsima_user_DllExport AckermannDrivePubSubType(); + + eProsima_user_DllExport virtual ~AckermannDrivePubSubType(); + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return true; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return true; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + new (memory) AckermannDrive(); + return true; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; +}; +} // namespace msg +} // namespace ackermann_msgs + +#endif // _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/AckermannDriveStamped.cpp b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStamped.cxx similarity index 85% rename from LibCarla/source/carla/ros2/types/AckermannDriveStamped.cpp rename to LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStamped.cxx index 3d86e6193f4..d1d2fce8634 100644 --- a/LibCarla/source/carla/ros2/types/AckermannDriveStamped.cpp +++ b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStamped.cxx @@ -34,20 +34,11 @@ using namespace eprosima::fastcdr::exception; #include -#define builtin_interfaces_msg_Time_max_cdr_typesize 8ULL; -#define ackermann_msgs_msg_AckermannDriveStamped_max_cdr_typesize 288ULL; -#define ackermann_msgs_msg_AckermannDrive_max_cdr_typesize 20ULL; -#define std_msgs_msg_Header_max_cdr_typesize 268ULL; -#define builtin_interfaces_msg_Time_max_key_cdr_typesize 0ULL; -#define ackermann_msgs_msg_AckermannDriveStamped_max_key_cdr_typesize 0ULL; -#define ackermann_msgs_msg_AckermannDrive_max_key_cdr_typesize 0ULL; -#define std_msgs_msg_Header_max_key_cdr_typesize 0ULL; - ackermann_msgs::msg::AckermannDriveStamped::AckermannDriveStamped() { - // std_msgs::msg::Header m_header + // m_header com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@176b3f44 - // ackermann_msgs::msg::AckermannDrive m_drive + // m_drive com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@6ee6f53 } @@ -55,7 +46,6 @@ ackermann_msgs::msg::AckermannDriveStamped::AckermannDriveStamped() ackermann_msgs::msg::AckermannDriveStamped::~AckermannDriveStamped() { - } ackermann_msgs::msg::AckermannDriveStamped::AckermannDriveStamped( @@ -66,7 +56,7 @@ ackermann_msgs::msg::AckermannDriveStamped::AckermannDriveStamped( } ackermann_msgs::msg::AckermannDriveStamped::AckermannDriveStamped( - AckermannDriveStamped&& x) noexcept + AckermannDriveStamped&& x) { m_header = std::move(x.m_header); m_drive = std::move(x.m_drive); @@ -83,7 +73,7 @@ ackermann_msgs::msg::AckermannDriveStamped& ackermann_msgs::msg::AckermannDriveS } ackermann_msgs::msg::AckermannDriveStamped& ackermann_msgs::msg::AckermannDriveStamped::operator =( - AckermannDriveStamped&& x) noexcept + AckermannDriveStamped&& x) { m_header = std::move(x.m_header); @@ -108,8 +98,13 @@ bool ackermann_msgs::msg::AckermannDriveStamped::operator !=( size_t ackermann_msgs::msg::AckermannDriveStamped::getMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return ackermann_msgs_msg_AckermannDriveStamped_max_cdr_typesize; + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getMaxCdrSerializedSize(current_alignment); + current_alignment += ackermann_msgs::msg::AckermannDrive::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; } size_t ackermann_msgs::msg::AckermannDriveStamped::getCdrSerializedSize( @@ -218,12 +213,14 @@ ackermann_msgs::msg::AckermannDrive& ackermann_msgs::msg::AckermannDriveStamped: return m_drive; } - size_t ackermann_msgs::msg::AckermannDriveStamped::getKeyMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return ackermann_msgs_msg_AckermannDriveStamped_max_key_cdr_typesize; + size_t current_align = current_alignment; + + + + return current_align; } bool ackermann_msgs::msg::AckermannDriveStamped::isKeyDefined() @@ -235,7 +232,7 @@ void ackermann_msgs::msg::AckermannDriveStamped::serializeKey( eprosima::fastcdr::Cdr& scdr) const { (void) scdr; + } - diff --git a/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStamped.h b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStamped.h new file mode 100644 index 00000000000..472e5779790 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStamped.h @@ -0,0 +1,221 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AckermannDriveStamped.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPED_H_ +#define _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPED_H_ + +#include "AckermannDrive.h" +#include "std_msgs/msg/Header.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(AckermannDriveStamped_SOURCE) +#define AckermannDriveStamped_DllAPI __declspec(dllexport) +#else +#define AckermannDriveStamped_DllAPI __declspec(dllimport) +#endif // AckermannDriveStamped_SOURCE +#else +#define AckermannDriveStamped_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define AckermannDriveStamped_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace ackermann_msgs { +namespace msg { +/*! + * @brief This class represents the structure AckermannDriveStamped defined by the user in the IDL file. + * @ingroup ACKERMANNDRIVESTAMPED + */ +class AckermannDriveStamped { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport AckermannDriveStamped(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~AckermannDriveStamped(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object ackermann_msgs::msg::AckermannDriveStamped that will be copied. + */ + eProsima_user_DllExport AckermannDriveStamped(const AckermannDriveStamped& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object ackermann_msgs::msg::AckermannDriveStamped that will be copied. + */ + eProsima_user_DllExport AckermannDriveStamped(AckermannDriveStamped&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object ackermann_msgs::msg::AckermannDriveStamped that will be copied. + */ + eProsima_user_DllExport AckermannDriveStamped& operator=(const AckermannDriveStamped& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object ackermann_msgs::msg::AckermannDriveStamped that will be copied. + */ + eProsima_user_DllExport AckermannDriveStamped& operator=(AckermannDriveStamped&& x); + + /*! + * @brief Comparison operator. + * @param x ackermann_msgs::msg::AckermannDriveStamped object to compare. + */ + eProsima_user_DllExport bool operator==(const AckermannDriveStamped& x) const; + + /*! + * @brief Comparison operator. + * @param x ackermann_msgs::msg::AckermannDriveStamped object to compare. + */ + eProsima_user_DllExport bool operator!=(const AckermannDriveStamped& x) const; + + /*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ + eProsima_user_DllExport void header(const std_msgs::msg::Header& _header); + + /*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ + eProsima_user_DllExport void header(std_msgs::msg::Header&& _header); + + /*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ + eProsima_user_DllExport const std_msgs::msg::Header& header() const; + + /*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ + eProsima_user_DllExport std_msgs::msg::Header& header(); + /*! + * @brief This function copies the value in member drive + * @param _drive New value to be copied in member drive + */ + eProsima_user_DllExport void drive(const ackermann_msgs::msg::AckermannDrive& _drive); + + /*! + * @brief This function moves the value in member drive + * @param _drive New value to be moved in member drive + */ + eProsima_user_DllExport void drive(ackermann_msgs::msg::AckermannDrive&& _drive); + + /*! + * @brief This function returns a constant reference to member drive + * @return Constant reference to member drive + */ + eProsima_user_DllExport const ackermann_msgs::msg::AckermannDrive& drive() const; + + /*! + * @brief This function returns a reference to member drive + * @return Reference to member drive + */ + eProsima_user_DllExport ackermann_msgs::msg::AckermannDrive& drive(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const ackermann_msgs::msg::AckermannDriveStamped& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + std_msgs::msg::Header m_header; + ackermann_msgs::msg::AckermannDrive m_drive; +}; +} // namespace msg +} // namespace ackermann_msgs + +#endif // _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPED_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/AckermannDriveStampedPubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStampedPubSubTypes.cxx similarity index 85% rename from LibCarla/source/carla/ros2/types/AckermannDriveStampedPubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStampedPubSubTypes.cxx index edba64f67ec..5427bc5febf 100644 --- a/LibCarla/source/carla/ros2/types/AckermannDriveStampedPubSubTypes.cpp +++ b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStampedPubSubTypes.cxx @@ -62,15 +62,15 @@ namespace ackermann_msgs { // Object that serializes the data. eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); try { - // Serialize encapsulation - ser.serialize_encapsulation(); // Serialize the object. p_type->serialize(ser); } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) { return false; } @@ -84,25 +84,25 @@ namespace ackermann_msgs { SerializedPayload_t* payload, void* data) { - try - { - // Convert DATA to pointer of your type - AckermannDriveStamped* p_type = static_cast(data); + //Convert DATA to pointer of your type + AckermannDriveStamped* p_type = static_cast(data); - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); - // Deserialize encapsulation. - deser.read_encapsulation(); - payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + try + { // Deserialize the object. p_type->deserialize(deser); } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) { return false; } @@ -173,6 +173,4 @@ namespace ackermann_msgs { } //End of namespace msg - } //End of namespace ackermann_msgs - diff --git a/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStampedPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStampedPubSubTypes.h new file mode 100644 index 00000000000..86aedb8db10 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStampedPubSubTypes.h @@ -0,0 +1,92 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AckermannDriveStampedPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPED_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPED_PUBSUBTYPES_H_ + +#include +#include + +#include "AckermannDriveStamped.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated AckermannDriveStamped is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace ackermann_msgs { +namespace msg { +/*! + * @brief This class represents the TopicDataType of the type AckermannDriveStamped defined by the user in the IDL file. + * @ingroup ACKERMANNDRIVESTAMPED + */ +class AckermannDriveStampedPubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef AckermannDriveStamped type; + + eProsima_user_DllExport AckermannDriveStampedPubSubType(); + + eProsima_user_DllExport virtual ~AckermannDriveStampedPubSubType(); + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + (void)memory; + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; +}; +} // namespace msg +} // namespace ackermann_msgs + +#endif // _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPED_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/Time.cpp b/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/Time.cxx similarity index 88% rename from LibCarla/source/carla/ros2/types/Time.cpp rename to LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/Time.cxx index 95f2e7b95ce..3191854d26b 100644 --- a/LibCarla/source/carla/ros2/types/Time.cpp +++ b/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/Time.cxx @@ -34,19 +34,18 @@ using namespace eprosima::fastcdr::exception; #include -#define builtin_interfaces_msg_Time_max_cdr_typesize 8ULL; -#define builtin_interfaces_msg_Time_max_key_cdr_typesize 0ULL; - builtin_interfaces::msg::Time::Time() { - // long m_sec + // m_sec com.eprosima.idl.parser.typecode.PrimitiveTypeCode@d23e042 m_sec = 0; - // unsigned long m_nanosec + // m_nanosec com.eprosima.idl.parser.typecode.PrimitiveTypeCode@46d59067 m_nanosec = 0; + } builtin_interfaces::msg::Time::~Time() { + } builtin_interfaces::msg::Time::Time( @@ -57,7 +56,7 @@ builtin_interfaces::msg::Time::Time( } builtin_interfaces::msg::Time::Time( - Time&& x) noexcept + Time&& x) { m_sec = x.m_sec; m_nanosec = x.m_nanosec; @@ -66,6 +65,7 @@ builtin_interfaces::msg::Time::Time( builtin_interfaces::msg::Time& builtin_interfaces::msg::Time::operator =( const Time& x) { + m_sec = x.m_sec; m_nanosec = x.m_nanosec; @@ -73,8 +73,9 @@ builtin_interfaces::msg::Time& builtin_interfaces::msg::Time::operator =( } builtin_interfaces::msg::Time& builtin_interfaces::msg::Time::operator =( - Time&& x) noexcept + Time&& x) { + m_sec = x.m_sec; m_nanosec = x.m_nanosec; @@ -84,6 +85,7 @@ builtin_interfaces::msg::Time& builtin_interfaces::msg::Time::operator =( bool builtin_interfaces::msg::Time::operator ==( const Time& x) const { + return (m_sec == x.m_sec && m_nanosec == x.m_nanosec); } @@ -96,8 +98,17 @@ bool builtin_interfaces::msg::Time::operator !=( size_t builtin_interfaces::msg::Time::getMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return builtin_interfaces_msg_Time_max_cdr_typesize; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + + return current_alignment - initial_alignment; } size_t builtin_interfaces::msg::Time::getCdrSerializedSize( @@ -106,22 +117,31 @@ size_t builtin_interfaces::msg::Time::getCdrSerializedSize( { (void)data; size_t initial_alignment = current_alignment; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + return current_alignment - initial_alignment; } void builtin_interfaces::msg::Time::serialize( eprosima::fastcdr::Cdr& scdr) const { + scdr << m_sec; scdr << m_nanosec; + } void builtin_interfaces::msg::Time::deserialize( eprosima::fastcdr::Cdr& dcdr) { + dcdr >> m_sec; dcdr >> m_nanosec; } @@ -182,11 +202,15 @@ uint32_t& builtin_interfaces::msg::Time::nanosec() return m_nanosec; } + size_t builtin_interfaces::msg::Time::getKeyMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return builtin_interfaces_msg_Time_max_key_cdr_typesize; + size_t current_align = current_alignment; + + + + return current_align; } bool builtin_interfaces::msg::Time::isKeyDefined() @@ -198,4 +222,7 @@ void builtin_interfaces::msg::Time::serializeKey( eprosima::fastcdr::Cdr& scdr) const { (void) scdr; + } + + diff --git a/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/Time.h b/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/Time.h new file mode 100644 index 00000000000..ae55bc39467 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/Time.h @@ -0,0 +1,207 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Time.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIME_H_ +#define _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIME_H_ + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(Time_SOURCE) +#define Time_DllAPI __declspec(dllexport) +#else +#define Time_DllAPI __declspec(dllimport) +#endif // Time_SOURCE +#else +#define Time_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define Time_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace builtin_interfaces { +namespace msg { +/*! + * @brief This class represents the structure Time defined by the user in the IDL file. + * @ingroup TIME + */ +class Time { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Time(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Time(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object builtin_interfaces::msg::Time that will be copied. + */ + eProsima_user_DllExport Time(const Time& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object builtin_interfaces::msg::Time that will be copied. + */ + eProsima_user_DllExport Time(Time&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object builtin_interfaces::msg::Time that will be copied. + */ + eProsima_user_DllExport Time& operator=(const Time& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object builtin_interfaces::msg::Time that will be copied. + */ + eProsima_user_DllExport Time& operator=(Time&& x); + + /*! + * @brief Comparison operator. + * @param x builtin_interfaces::msg::Time object to compare. + */ + eProsima_user_DllExport bool operator==(const Time& x) const; + + /*! + * @brief Comparison operator. + * @param x builtin_interfaces::msg::Time object to compare. + */ + eProsima_user_DllExport bool operator!=(const Time& x) const; + + /*! + * @brief This function sets a value in member sec + * @param _sec New value for member sec + */ + eProsima_user_DllExport void sec(int32_t _sec); + + /*! + * @brief This function returns the value of member sec + * @return Value of member sec + */ + eProsima_user_DllExport int32_t sec() const; + + /*! + * @brief This function returns a reference to member sec + * @return Reference to member sec + */ + eProsima_user_DllExport int32_t& sec(); + + /*! + * @brief This function sets a value in member nanosec + * @param _nanosec New value for member nanosec + */ + eProsima_user_DllExport void nanosec(uint32_t _nanosec); + + /*! + * @brief This function returns the value of member nanosec + * @return Value of member nanosec + */ + eProsima_user_DllExport uint32_t nanosec() const; + + /*! + * @brief This function returns a reference to member nanosec + * @return Reference to member nanosec + */ + eProsima_user_DllExport uint32_t& nanosec(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const builtin_interfaces::msg::Time& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + int32_t m_sec; + uint32_t m_nanosec; +}; +} // namespace msg +} // namespace builtin_interfaces + +#endif // _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIME_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/TimePubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/TimePubSubTypes.cxx similarity index 90% rename from LibCarla/source/carla/ros2/types/TimePubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/TimePubSubTypes.cxx index 8bb4969d9ad..ca1c7915dda 100644 --- a/LibCarla/source/carla/ros2/types/TimePubSubTypes.cpp +++ b/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/TimePubSubTypes.cxx @@ -19,6 +19,7 @@ * This file was generated by the tool fastcdrgen. */ + #include #include @@ -63,7 +64,17 @@ namespace builtin_interfaces { payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; // Serialize encapsulation ser.serialize_encapsulation(); - p_type->serialize(ser); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + // Get the serialized length payload->length = static_cast(ser.getSerializedDataLength()); return true; @@ -86,8 +97,15 @@ namespace builtin_interfaces { deser.read_encapsulation(); payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - // Deserialize the object. - p_type->deserialize(deser); + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } return true; } @@ -151,5 +169,8 @@ namespace builtin_interfaces { } return true; } + + } //End of namespace msg + } //End of namespace builtin_interfaces diff --git a/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/TimePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/TimePubSubTypes.h new file mode 100644 index 00000000000..919dd66069d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/TimePubSubTypes.h @@ -0,0 +1,91 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file TimePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIME_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIME_PUBSUBTYPES_H_ + +#include +#include + +#include "Time.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated Time is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace builtin_interfaces { +namespace msg { +/*! + * @brief This class represents the TopicDataType of the type Time defined by the user in the IDL file. + * @ingroup TIME + */ +class TimePubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef Time type; + + eProsima_user_DllExport TimePubSubType(); + + eProsima_user_DllExport virtual ~TimePubSubType(); + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return true; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return true; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + new (memory) Time(); + return true; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; +}; +} // namespace msg +} // namespace builtin_interfaces + +#endif // _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIME_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsDomainParticipantImpl.cpp b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsDomainParticipantImpl.cpp new file mode 100644 index 00000000000..b498e27cc99 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsDomainParticipantImpl.cpp @@ -0,0 +1,51 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/ros2/impl/DdsDomainParticipantImpl.h" + +#include +#include + +#include +#include + +#include "carla/Logging.h" + +namespace carla { +namespace ros2 { + +DdsDomainParticipantImpl::DdsDomainParticipantImpl() { + _factory = eprosima::fastdds::dds::DomainParticipantFactory::get_shared_instance(); + if (_factory == nullptr) { + carla::log_error("DdsDomainParticipantImpl(): Failed to acquire DomainParticipantFactory"); + return; + } + + const char *ros_domain_id_env = std::getenv("ROS_DOMAIN_ID"); + unsigned int ros_domain_id = 0; + if ( ros_domain_id_env != nullptr ) { + try { + ros_domain_id = (unsigned int)(std::atoi(ros_domain_id_env)); + } catch (...) { + ros_domain_id = 0; + } + } + auto pqos = eprosima::fastdds::dds::PARTICIPANT_QOS_DEFAULT; + pqos.name("carla-server"); + _participant = _factory->create_participant(ros_domain_id, pqos); + if (_participant == nullptr) { + carla::log_error("DdsDomainParticipantImpl(): Failed to create DomainParticipant"); + } +} + +DdsDomainParticipantImpl::~DdsDomainParticipantImpl() { + carla::log_warning("DdsDomainParticipantImpl::Destructor()"); + if ((_participant != nullptr) && (_factory != nullptr)) { + _factory->delete_participant(_participant); + _participant=nullptr; + } +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsDomainParticipantImpl.h b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsDomainParticipantImpl.h new file mode 100644 index 00000000000..1b8f7612adb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsDomainParticipantImpl.h @@ -0,0 +1,30 @@ + +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +namespace carla { +namespace ros2 { + +class DdsDomainParticipantImpl { +public: + DdsDomainParticipantImpl(); + ~DdsDomainParticipantImpl(); + + eprosima::fastdds::dds::DomainParticipant* GetDomainParticipant() { + return _participant; + } + +private: + eprosima::fastdds::dds::DomainParticipant* _participant{nullptr}; + // keep also a copy of the factory that the underlying DDS is keeping their stuff up + std::shared_ptr _factory; +}; + +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsPublisherImpl.h b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsPublisherImpl.h new file mode 100644 index 00000000000..cde7eb11dcd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsPublisherImpl.h @@ -0,0 +1,182 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "builtin_interfaces/msg/Time.h" +#include "carla/ros2/impl/DdsDomainParticipantImpl.h" +#include "carla/ros2/impl/DdsQoS.h" +#include "carla/ros2/impl/DdsReturnCode.h" +#include "carla/ros2/publishers/PublisherInterface.h" + +namespace carla { +namespace ros2 { + +template +class DdsPublisherImpl : public PublisherInterface, eprosima::fastdds::dds::DataWriterListener { +public: + DdsPublisherImpl() = default; + + virtual ~DdsPublisherImpl() { + carla::log_info("DdsPublisherImpl[", _topic != nullptr ? _topic->get_name() : "nulltopic", "]::Destructor()"); + if (_datawriter) { + _publisher->delete_datawriter(_datawriter); + _datawriter = nullptr; + } + + if (_publisher) { + _participant->delete_publisher(_publisher); + _publisher = nullptr; + } + + if (_topic) { + _participant->delete_topic(_topic); + _topic = nullptr; + } + } + + /** + * Initialize with PREALLOCATED_WITH_REALLOC_MEMORY_MODE memory policy. + * Use this initialization mode when dealing with larger sequence data types + * See //https://github.com/eProsima/Fast-DDS/issues/2330 for details + */ + bool InitHistoryPreallocatedWithReallocMemoryMode(std::shared_ptr domain_participant, + std::string topic_name, ROS2QoS qos) { + auto pubqos = PublisherQos(qos); + auto wqos = DataWriterQos(qos); + auto tqos = TopicQos(qos); + wqos.endpoint().history_memory_policy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + return InitInternal(domain_participant, topic_name, tqos, pubqos, wqos); + } + + bool Init(std::shared_ptr domain_participant, std::string topic_name, ROS2QoS qos) { + auto pubqos = PublisherQos(qos); + auto wqos = DataWriterQos(qos); + auto tqos = TopicQos(qos); + return InitInternal(domain_participant, topic_name, tqos, pubqos, wqos); + } + + bool Publish() override { + if (_message_updated) { + carla::log_debug("DdsPublisherImpl[", _topic->get_name(), "]::Publishing() updated message"); + eprosima::fastrtps::rtps::InstanceHandle_t instance_handle; + auto rcode = _datawriter->write(&_message, instance_handle); + if (rcode == eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_OK) { + _message_updated = false; + } else { + carla::log_error("DdsPublisherImpl[", _topic->get_name(), "]::Publish() Failed to write data; Error ", + std::to_string(rcode)); + } + carla::log_debug("DdsPublisherImpl[", _topic->get_name(), "]::Publishing() done"); + } + return !_message_updated; + } + + /** + * Mark the message as updated. This is required to ensure the Publish() call sends the message actually out. + */ + void SetMessageUpdated() { + _message_updated = true; + } + + /** + * If the last message was sent out or the message has never been set to updated, this returns \c true + * indicating the publisher to be able to overwrite the message. + */ + bool WasMessagePublished() { + return !_message_updated; + } + + /** + * Initialize the message header. This function is only valid if the message type provided supports a header! + * Implicitly calls SetMessageUpdated() to mark the message to be updated, so that it is published by Publish(). + */ + void SetMessageHeader(const builtin_interfaces::msg::Time& stamp, const std::string& frame_id) { + _message.header().stamp(stamp); + _message.header().frame_id(frame_id); + SetMessageUpdated(); + } + + /** + * Access the message data + */ + MESSAGE_TYPE& Message() { + return _message; + } + + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override { + return _matched > 0; + } + +private: + bool InitInternal(std::shared_ptr domain_participant, std::string topic_name, + eprosima::fastdds::dds::TopicQos const& tqos, eprosima::fastdds::dds::PublisherQos const& pubqos, + eprosima::fastdds::dds::DataWriterQos const& wqos) { + carla::log_info("DdsPublisherImpl[", topic_name, "]::Init()"); + + if (_type == nullptr) { + carla::log_error("DdsPublisherImpl::Init() Invalid TypeSupport"); + return false; + } + + _participant = domain_participant->GetDomainParticipant(); + if (_participant == nullptr) { + carla::log_error("DdsPublisherImpl[", _type->getName(), "]::Init() Invalid Participant"); + return false; + } + + _type.register_type(_participant); + + _publisher = _participant->create_publisher(pubqos); + if (_publisher == nullptr) { + carla::log_error("DdsPublisherImpl[", _type->getName(), "]::Init() Failed to create Publisher"); + return false; + } + + _topic = _participant->create_topic(topic_name, _type->getName(), tqos); + if (_topic == nullptr) { + carla::log_error("DdsPublisherImpl[", _type->getName(), "]::Init() Failed to create Topic for ", topic_name); + return false; + } + + eprosima::fastdds::dds::DataWriterListener* listener = + static_cast(this); + _datawriter = _publisher->create_datawriter(_topic, wqos, listener); + if (_datawriter == nullptr) { + carla::log_error("DdsPublisherImpl[", _topic->get_name(), "]::Init() Failed to create DataWriter"); + return false; + } + return true; + } + + void on_publication_matched(eprosima::fastdds::dds::DataWriter*, + const eprosima::fastdds::dds::PublicationMatchedStatus& info) override { + _matched = info.current_count; + carla::log_info("DdsPublisherImpl[", _topic->get_name(), "]::on_publication_matched(): ", _matched); + } + + eprosima::fastdds::dds::DomainParticipant* _participant{nullptr}; + eprosima::fastdds::dds::Publisher* _publisher{nullptr}; + eprosima::fastdds::dds::Topic* _topic{nullptr}; + eprosima::fastdds::dds::DataWriter* _datawriter{nullptr}; + eprosima::fastdds::dds::TypeSupport _type{new MESSAGE_PUB_TYPE()}; + MESSAGE_TYPE _message{}; + int _matched{0}; + bool _message_updated{false}; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsQoS.h b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsQoS.h new file mode 100644 index 00000000000..167f7f084fd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsQoS.h @@ -0,0 +1,68 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include +#include +#include +#include +#include "carla/ros2/ROS2QoS.h" + +namespace carla { +namespace ros2 { + +template +FAST_DDS_QOS_TYPE FastDdsQos(ROS2QoS const &qos) { + FAST_DDS_QOS_TYPE fast_dds_qos = fast_dds_default_qos; + + if (qos._reliability == ROS2QoS::Reliability::BEST_EFFORT) { + fast_dds_qos.reliability().kind = eprosima::fastdds::dds::ReliabilityQosPolicyKind::BEST_EFFORT_RELIABILITY_QOS; + } else if (qos._reliability == ROS2QoS::Reliability::RELIABLE) { + fast_dds_qos.reliability().kind = eprosima::fastdds::dds::ReliabilityQosPolicyKind::RELIABLE_RELIABILITY_QOS; + } + + if (qos._durability == ROS2QoS::Durability::VOLATILE) { + fast_dds_qos.durability().kind = eprosima::fastdds::dds::DurabilityQosPolicyKind::VOLATILE_DURABILITY_QOS; + } else if (qos._durability == ROS2QoS::Durability::TRANSIENT_LOCAL) { + fast_dds_qos.durability().kind = eprosima::fastdds::dds::DurabilityQosPolicyKind::TRANSIENT_LOCAL_DURABILITY_QOS; + } + + if (qos._history == ROS2QoS::History::KEEP_LAST) { + fast_dds_qos.history().kind = eprosima::fastdds::dds::HistoryQosPolicyKind::KEEP_LAST_HISTORY_QOS; + fast_dds_qos.history().depth = qos._history_depth; + } else if (qos._history == ROS2QoS::History::KEEP_ALL) { + fast_dds_qos.history().kind = eprosima::fastdds::dds::HistoryQosPolicyKind::KEEP_ALL_HISTORY_QOS; + fast_dds_qos.history().depth = qos._history_depth; + } + return fast_dds_qos; +} + +inline eprosima::fastdds::dds::TopicQos TopicQos(ROS2QoS const &qos) { + return FastDdsQos(qos); +} + +inline eprosima::fastdds::dds::DataWriterQos DataWriterQos(ROS2QoS const &qos) { + return FastDdsQos(qos); +} + +inline eprosima::fastdds::dds::DataReaderQos DataReaderQos(ROS2QoS const &qos) { + return FastDdsQos(qos); +} + +inline eprosima::fastdds::dds::PublisherQos PublisherQos(ROS2QoS const &qos) { + (void)qos; + eprosima::fastdds::dds::PublisherQos pubqos = eprosima::fastdds::dds::PUBLISHER_QOS_DEFAULT; + return pubqos; +} + +inline eprosima::fastdds::dds::SubscriberQos SubscriberQos(ROS2QoS const &qos) { + (void)qos; + eprosima::fastdds::dds::SubscriberQos subqos = eprosima::fastdds::dds::SUBSCRIBER_QOS_DEFAULT; + return subqos; +} + +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsReturnCode.h b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsReturnCode.h new file mode 100644 index 00000000000..0a87ba8055a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsReturnCode.h @@ -0,0 +1,48 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include + +#include + +namespace std { + +inline std::string to_string(eprosima::fastrtps::types::ReturnCode_t rcode) { + switch (rcode()) { + case eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_OK: + return "RETCODE_OK"; + case eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_ERROR: + return "RETCODE_ERROR"; + case eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_UNSUPPORTED: + return "RETCODE_UNSUPPORTED"; + case eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_BAD_PARAMETER: + return "RETCODE_BAD_PARAMETER"; + case eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_PRECONDITION_NOT_MET: + return "RETCODE_PRECONDITION_NOT_MET"; + case eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_OUT_OF_RESOURCES: + return "RETCODE_OUT_OF_RESOURCES"; + case eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_NOT_ENABLED: + return "RETCODE_NOT_ENABLED"; + case eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_IMMUTABLE_POLICY: + return "RETCODE_IMMUTABLE_POLICY"; + case eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_INCONSISTENT_POLICY: + return "RETCODE_INCONSISTENT_POLICY"; + case eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_ALREADY_DELETED: + return "RETCODE_ALREADY_DELETED"; + case eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_TIMEOUT: + return "RETCODE_TIMEOUT"; + case eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_NO_DATA: + return "RETCODE_NO_DATA"; + case eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_ILLEGAL_OPERATION: + return "RETCODE_ILLEGAL_OPERATION"; + case eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_NOT_ALLOWED_BY_SECURITY: + return "RETCODE_NOT_ALLOWED_BY_SECURITY"; + default: + return "UNKNOWN"; + } +} + +} // namespace std \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsServiceImpl.h b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsServiceImpl.h new file mode 100644 index 00000000000..c18d146d82e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsServiceImpl.h @@ -0,0 +1,215 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "carla/Logging.h" +#include "carla/ros2/impl/DdsDomainParticipantImpl.h" +#include "carla/ros2/impl/DdsQoS.h" +#include "carla/ros2/impl/DdsReturnCode.h" +#include "carla/ros2/services/ServiceInterface.h" + +namespace carla { +namespace ros2 { + +template +class DdsServiceImpl : public ServiceInterface, public eprosima::fastdds::dds::DataReaderListener { +public: + DdsServiceImpl() = default; + + virtual ~DdsServiceImpl() { + carla::log_info("DdsServiceImpl[", _request_topic != nullptr ? _request_topic->get_name() : "nulltopic", + "]::Destructor()"); + + if (_datawriter) { + _publisher->delete_datawriter(_datawriter); + _datawriter = nullptr; + } + + if (_publisher) { + _participant->delete_publisher(_publisher); + _publisher = nullptr; + } + + if (_response_topic) { + _participant->delete_topic(_response_topic); + _response_topic = nullptr; + } + + if (_datareader) { + _subscriber->delete_datareader(_datareader); + _datareader = nullptr; + } + + if (_subscriber) { + _participant->delete_subscriber(_subscriber); + _subscriber = nullptr; + } + + if (_request_topic) { + _participant->delete_topic(_request_topic); + _request_topic = nullptr; + } + } + + bool Init(std::shared_ptr domain_participant, std::string topic_name) { + carla::log_info("DdsServiceImpl[", topic_name, "]::Init()"); + + _participant = domain_participant->GetDomainParticipant(); + if (_participant == nullptr) { + carla::log_error("DdsServiceImpl[", topic_name, "]::Init(): Invalid Participant"); + return false; + } + + auto request_name = topic_name + "Request"; + request_name.replace(0u, 2u, "rq"); + if (_request_type == nullptr) { + carla::log_error("DdsServiceImpl[", topic_name, "]::Init(): Invalid Request TypeSupport"); + return false; + } + _request_type.register_type(_participant); + auto topic_qos = eprosima::fastdds::dds::TOPIC_QOS_DEFAULT; + topic_qos.history().kind = eprosima::fastdds::dds::KEEP_ALL_HISTORY_QOS; + topic_qos.reliability().kind = eprosima::fastdds::dds::RELIABLE_RELIABILITY_QOS; + _request_topic = + _participant->create_topic(request_name, _request_type->getName(), topic_qos); + if (_request_topic == nullptr) { + carla::log_error("DdsServiceImpl[", topic_name, "]::Init(): Failed to create Request Topic"); + return false; + } + auto subscriber_qos= eprosima::fastdds::dds::SUBSCRIBER_QOS_DEFAULT; + _subscriber = _participant->create_subscriber(subscriber_qos); + if (_subscriber == nullptr) { + carla::log_error("DdsServiceImpl[", topic_name, "]::Init(): Failed to create Subscriber"); + return false; + } + eprosima::fastdds::dds::DataReaderListener* reader_listener = + static_cast(this); + auto datareader_qos = eprosima::fastdds::dds::DATAREADER_QOS_DEFAULT; + datareader_qos.history().kind = eprosima::fastdds::dds::KEEP_ALL_HISTORY_QOS; + datareader_qos.reliability().kind = eprosima::fastdds::dds::RELIABLE_RELIABILITY_QOS; + _datareader = + _subscriber->create_datareader(_request_topic, datareader_qos, reader_listener); + if (_datareader == nullptr) { + carla::log_error("DdsServiceImpl[", topic_name, "]::Init(): Failed to create DataReader"); + return false; + } + + auto response_name = topic_name + "Reply"; + response_name.replace(0u, 2u, "rr"); + if (_resonse_type == nullptr) { + carla::log_error("DdsServiceImpl[", topic_name, "]::Init(): Invalid Response TypeSupport"); + return false; + } + _resonse_type.register_type(_participant); + _response_topic = + _participant->create_topic(response_name, _resonse_type->getName(), topic_qos); + if (_response_topic == nullptr) { + carla::log_error("DdsServiceImpl[", topic_name, "]::Init(): Failed to create Response Topic"); + return false; + } + auto publisher_qos = eprosima::fastdds::dds::PUBLISHER_QOS_DEFAULT; + _publisher = _participant->create_publisher(publisher_qos); + if (_publisher == nullptr) { + carla::log_error("DdsServiceImpl[", _response_topic->get_name(), "]::Init() Failed to create Publisher"); + return false; + } + + auto writer_qos = eprosima::fastdds::dds::DATAWRITER_QOS_DEFAULT; + writer_qos.endpoint().history_memory_policy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + writer_qos.history().kind = eprosima::fastdds::dds::KEEP_ALL_HISTORY_QOS; + writer_qos.durability().kind = eprosima::fastdds::dds::TRANSIENT_LOCAL_DURABILITY_QOS; + writer_qos.reliability().kind = eprosima::fastdds::dds::RELIABLE_RELIABILITY_QOS; + _datawriter = _publisher->create_datawriter(_response_topic, writer_qos); + if (_datawriter == nullptr) { + carla::log_error("DdsServiceImpl[", _response_topic->get_name(), "]::Init() Failed to create DataWriter"); + return false; + } + + return true; + } + + using ServiceCallbackType = std::function; + void SetServiceCallback(ServiceCallbackType callback) { + _callback = callback; + } + + void on_data_available(eprosima::fastdds::dds::DataReader* reader) override { + eprosima::fastdds::dds::SampleInfo info; + REQUEST_TYPE request; + auto rcode = reader->take_next_sample(&request, &info); + if (rcode == eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_OK) { + if (eprosima::fastdds::dds::InstanceStateKind::ALIVE_INSTANCE_STATE == info.instance_state) { + carla::log_debug("DdsServiceImpl[", _request_topic->get_name(), "]::on_data_available(): Incoming request "); + _incoming_requests.push_back({request, info.sample_identity}); + } else { + carla::log_error("DdsServiceImpl[", _request_topic->get_name(), + "]::on_data_available(): Error not a request instance"); + } + } else { + carla::log_error("DdsServiceImpl[", _request_topic->get_name(), "]::on_data_available(): Error ", + std::to_string(rcode)); + } + } + + void CheckRequest() override { + if (!_callback) { + carla::log_warning("DdsServiceImpl[", _request_topic->get_name(), "]::CheckRequest(): No callback defined yet"); + return; + } + while (!_incoming_requests.empty()) { + carla::log_debug("DdsServiceImpl[", _request_topic->get_name(), "]::CheckRequest(): New Request"); + auto const incoming_request = _incoming_requests.front(); + RESPONSE_TYPE response = _callback(incoming_request._request); + carla::log_debug("DdsServiceImpl[", _response_topic->get_name(), "]::CheckRequest(): Callback returned"); + + eprosima::fastrtps::rtps::WriteParams write_params; + write_params.related_sample_identity() = incoming_request._request_identity; + auto rcode = _datawriter->write(reinterpret_cast(&response), write_params); + if (rcode != bool(eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_OK)) { + // strange: getting error while the result is actually sent out + carla::log_debug("DdsServiceImpl[", _response_topic->get_name(), + "]::CheckRequest() Failed to write data; Error ", std::to_string(rcode)); + } + carla::log_debug("DdsServiceImpl[", _response_topic->get_name(), "]::CheckRequest() Response sent"); + + _incoming_requests.pop_front(); + } + } + +private: + eprosima::fastdds::dds::DomainParticipant* _participant{nullptr}; + + eprosima::fastdds::dds::TypeSupport _request_type{new REQUEST_PUB_TYPE()}; + eprosima::fastdds::dds::Topic* _request_topic{nullptr}; + eprosima::fastdds::dds::Subscriber* _subscriber{nullptr}; + eprosima::fastdds::dds::DataReader* _datareader{nullptr}; + + eprosima::fastdds::dds::TypeSupport _resonse_type{new RESPONSE_PUB_TYPE()}; + eprosima::fastdds::dds::Topic* _response_topic{nullptr}; + eprosima::fastdds::dds::Publisher* _publisher{nullptr}; + eprosima::fastdds::dds::DataWriter* _datawriter{nullptr}; + + ServiceCallbackType _callback{nullptr}; + + struct IncomingRequest { + REQUEST_TYPE _request{}; + eprosima::fastrtps::rtps::SampleIdentity _request_identity; + }; + std::deque _incoming_requests; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsSubscriberImpl.h b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsSubscriberImpl.h new file mode 100644 index 00000000000..4fa72f9a5b4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsSubscriberImpl.h @@ -0,0 +1,170 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include "carla/Logging.h" +#include "carla/ros2/impl/DdsDomainParticipantImpl.h" +#include "carla/ros2/impl/DdsQoS.h" +#include "carla/ros2/impl/DdsReturnCode.h" +#include "carla/ros2/subscribers/SubscriberImplBase.h" + +namespace carla { +namespace ros2 { + +template +class DdsSubscriberImpl : public SubscriberImplBase, public eprosima::fastdds::dds::DataReaderListener { +public: + using SubscriberImplBase::AddPublisher; + using SubscriberImplBase::NumberPublishersConnected; + using SubscriberImplBase::RemovePublisher; + using SubscriberImplBase::HasPublishersConnected; + using SubscriberImplBase::AddMessage; + + DdsSubscriberImpl(SubscriberBase& parent) : SubscriberImplBase(parent) {} + + virtual ~DdsSubscriberImpl() { + carla::log_info("DdsSubscriberImpl[", _topic->get_name(), "]::Destructor()"); + + if (_datareader) { + _subscriber->delete_datareader(_datareader); + _datareader = nullptr; + } + + if (_subscriber) { + _participant->delete_subscriber(_subscriber); + _subscriber = nullptr; + } + + if (_topic) { + _participant->delete_topic(_topic); + _topic = nullptr; + } + } + + bool Init(std::shared_ptr domain_participant, std::string topic_name, ROS2QoS qos) { + auto subqos = SubscriberQos(qos); + auto rqos = DataReaderQos(qos); + auto tqos = TopicQos(qos); + return InitInternal(domain_participant, topic_name, tqos, subqos, rqos); + } + + void on_subscription_matched(eprosima::fastdds::dds::DataReader* reader, + const eprosima::fastdds::dds::SubscriptionMatchedStatus& info) override { + auto const publisher_guid = GetPublisherGuid(info.last_publication_handle); + bool had_connected_publisher = HasPublishersConnected(); + + if (info.current_count_change < 0) { + RemovePublisher(publisher_guid); + carla::log_debug("DdsSubscriberImpl[", _topic->get_name(), "]::on_subscription_matched(", publisher_guid, + ") publisher disconnected. Connected publisher remaining: ", NumberPublishersConnected()); + } else { + AddPublisher(publisher_guid); + carla::log_debug("DdsSubscriberImpl[", _topic->get_name(), "]::on_subscription_matched(", publisher_guid, + ") publisher connected. Connected publisher: ", NumberPublishersConnected()); + } + + if (info.current_count != NumberPublishersConnected()) { + carla::log_error("DdsSubscriberImpl[", _topic->get_name(), "]::on_subscription_matched(", publisher_guid, + "): current_count=", info.current_count, + ", but publisher list not yet empty. Connected publisher: ", NumberPublishersConnected()); + } + carla::log_debug("DdsSubscriberImpl[", _topic->get_name(), "]::on_subscription_matched(", publisher_guid, + "): interface has" + " total_count=", + info.total_count, " total_count_change=", info.total_count_change, + " current_count=", info.current_count, " current_count_change=", info.current_count_change, + " handle-id=", info.last_publication_handle, " matched subscriptions and currently ", + NumberPublishersConnected(), " publisher connected."); + } + + void on_data_available(eprosima::fastdds::dds::DataReader* reader) override { + eprosima::fastdds::dds::SampleInfo info; + MESSAGE_TYPE message; + auto rcode = reader->take_next_sample(&message, &info); + auto const publisher_guid = GetPublisherGuid(info.publication_handle); + if (rcode == eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_OK) { + AddMessage(publisher_guid, message); + carla::log_debug("DdsSubscriberImpl[", _topic->get_name(), "]::on_data_available(): from client ", publisher_guid, + "and handle: ", info.publication_handle); + } else { + carla::log_error("DdsSubscriberImpl[", _topic->get_name(), "]::on_data_available(): Error ", + std::to_string(rcode)); + } + } + + bool InitInternal(std::shared_ptr domain_participant, std::string topic_name, + eprosima::fastdds::dds::TopicQos const& tqos, eprosima::fastdds::dds::SubscriberQos const& subqos, + eprosima::fastdds::dds::DataReaderQos const& rqos) { + carla::log_info("DdsSubscriberImpl[", topic_name, "]::Init()"); + + _participant = domain_participant->GetDomainParticipant(); + if (_participant == nullptr) { + carla::log_error("DdsSubscriberImpl[", topic_name, "]::Init(): Invalid Participant"); + return false; + } + + if (_type == nullptr) { + carla::log_error("DdsSubscriberImpl[", topic_name, "]::Init(): Invalid TypeSupport"); + return false; + } + + _type.register_type(_participant); + + _subscriber = _participant->create_subscriber(subqos); + if (_subscriber == nullptr) { + carla::log_error("DdsSubscriberImpl[", topic_name, "]::Init(): Failed to create Subscriber"); + return false; + } + + _topic = _participant->create_topic(topic_name, _type->getName(), tqos); + if (_topic == nullptr) { + carla::log_error("DdsSubscriberImpl[", topic_name, "]::Init(): Failed to create Topic"); + return false; + } + + eprosima::fastdds::dds::DataReaderListener* listener = + static_cast(this); + _datareader = _subscriber->create_datareader(_topic, rqos, listener); + if (_datareader == nullptr) { + carla::log_error("DdsSubscriberImpl[", topic_name, "]::Init(): Failed to create DataReader"); + return false; + } + return true; + } + + std::string GetPublisherGuid( + eprosima::fastdds::dds::InstanceHandle_t const& instance_handle) { + auto insert_result = _instance_handles.insert({instance_handle, ""}); + if ( insert_result.second ) { + // only perform the conversion from GUID to string once when inserted first time + eprosima::fastrtps::rtps::GUID_t guid(insert_result.first->first); + std::stringstream namestream; + namestream << guid; + insert_result.first->second = namestream.str(); + } + return insert_result.first->second; + } + + eprosima::fastdds::dds::DomainParticipant* _participant{nullptr}; + eprosima::fastdds::dds::Subscriber* _subscriber{nullptr}; + eprosima::fastdds::dds::Topic* _topic{nullptr}; + eprosima::fastdds::dds::DataReader* _datareader{nullptr}; + eprosima::fastdds::dds::TypeSupport _type{new MESSAGE_PUB_TYPE()}; + + std::map _instance_handles; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprint.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprint.cxx new file mode 100644 index 00000000000..e33b60b800f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprint.cxx @@ -0,0 +1,312 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaActorBlueprint.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaActorBlueprint.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaActorBlueprint::CarlaActorBlueprint() +{ + // m_id com.eprosima.idl.parser.typecode.StringTypeCode@971d0d8 + m_id =""; + // m_tags com.eprosima.idl.parser.typecode.SequenceTypeCode@51931956 + + // m_attributes com.eprosima.idl.parser.typecode.SequenceTypeCode@2b4a2ec7 + + +} + +carla_msgs::msg::CarlaActorBlueprint::~CarlaActorBlueprint() +{ + + +} + +carla_msgs::msg::CarlaActorBlueprint::CarlaActorBlueprint( + const CarlaActorBlueprint& x) +{ + m_id = x.m_id; + m_tags = x.m_tags; + m_attributes = x.m_attributes; +} + +carla_msgs::msg::CarlaActorBlueprint::CarlaActorBlueprint( + CarlaActorBlueprint&& x) +{ + m_id = std::move(x.m_id); + m_tags = std::move(x.m_tags); + m_attributes = std::move(x.m_attributes); +} + +carla_msgs::msg::CarlaActorBlueprint& carla_msgs::msg::CarlaActorBlueprint::operator =( + const CarlaActorBlueprint& x) +{ + + m_id = x.m_id; + m_tags = x.m_tags; + m_attributes = x.m_attributes; + + return *this; +} + +carla_msgs::msg::CarlaActorBlueprint& carla_msgs::msg::CarlaActorBlueprint::operator =( + CarlaActorBlueprint&& x) +{ + + m_id = std::move(x.m_id); + m_tags = std::move(x.m_tags); + m_attributes = std::move(x.m_attributes); + + return *this; +} + +bool carla_msgs::msg::CarlaActorBlueprint::operator ==( + const CarlaActorBlueprint& x) const +{ + + return (m_id == x.m_id && m_tags == x.m_tags && m_attributes == x.m_attributes); +} + +bool carla_msgs::msg::CarlaActorBlueprint::operator !=( + const CarlaActorBlueprint& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaActorBlueprint::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < 100; ++a) + { + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + } + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < 100; ++a) + { + current_alignment += diagnostic_msgs::msg::KeyValue::getMaxCdrSerializedSize(current_alignment);} + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaActorBlueprint::getCdrSerializedSize( + const carla_msgs::msg::CarlaActorBlueprint& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.id().size() + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < data.tags().size(); ++a) + { + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + + data.tags().at(a).size() + 1; + } + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < data.attributes().size(); ++a) + { + current_alignment += diagnostic_msgs::msg::KeyValue::getCdrSerializedSize(data.attributes().at(a), current_alignment);} + + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaActorBlueprint::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_id; + scdr << m_tags;scdr << m_attributes; + +} + +void carla_msgs::msg::CarlaActorBlueprint::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_id; + dcdr >> m_tags; + dcdr >> m_attributes; +} + +/*! + * @brief This function copies the value in member id + * @param _id New value to be copied in member id + */ +void carla_msgs::msg::CarlaActorBlueprint::id( + const std::string& _id) +{ + m_id = _id; +} + +/*! + * @brief This function moves the value in member id + * @param _id New value to be moved in member id + */ +void carla_msgs::msg::CarlaActorBlueprint::id( + std::string&& _id) +{ + m_id = std::move(_id); +} + +/*! + * @brief This function returns a constant reference to member id + * @return Constant reference to member id + */ +const std::string& carla_msgs::msg::CarlaActorBlueprint::id() const +{ + return m_id; +} + +/*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ +std::string& carla_msgs::msg::CarlaActorBlueprint::id() +{ + return m_id; +} +/*! + * @brief This function copies the value in member tags + * @param _tags New value to be copied in member tags + */ +void carla_msgs::msg::CarlaActorBlueprint::tags( + const std::vector& _tags) +{ + m_tags = _tags; +} + +/*! + * @brief This function moves the value in member tags + * @param _tags New value to be moved in member tags + */ +void carla_msgs::msg::CarlaActorBlueprint::tags( + std::vector&& _tags) +{ + m_tags = std::move(_tags); +} + +/*! + * @brief This function returns a constant reference to member tags + * @return Constant reference to member tags + */ +const std::vector& carla_msgs::msg::CarlaActorBlueprint::tags() const +{ + return m_tags; +} + +/*! + * @brief This function returns a reference to member tags + * @return Reference to member tags + */ +std::vector& carla_msgs::msg::CarlaActorBlueprint::tags() +{ + return m_tags; +} +/*! + * @brief This function copies the value in member attributes + * @param _attributes New value to be copied in member attributes + */ +void carla_msgs::msg::CarlaActorBlueprint::attributes( + const std::vector& _attributes) +{ + m_attributes = _attributes; +} + +/*! + * @brief This function moves the value in member attributes + * @param _attributes New value to be moved in member attributes + */ +void carla_msgs::msg::CarlaActorBlueprint::attributes( + std::vector&& _attributes) +{ + m_attributes = std::move(_attributes); +} + +/*! + * @brief This function returns a constant reference to member attributes + * @return Constant reference to member attributes + */ +const std::vector& carla_msgs::msg::CarlaActorBlueprint::attributes() const +{ + return m_attributes; +} + +/*! + * @brief This function returns a reference to member attributes + * @return Reference to member attributes + */ +std::vector& carla_msgs::msg::CarlaActorBlueprint::attributes() +{ + return m_attributes; +} + +size_t carla_msgs::msg::CarlaActorBlueprint::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaActorBlueprint::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaActorBlueprint::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprint.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprint.h new file mode 100644 index 00000000000..64f09476123 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprint.h @@ -0,0 +1,269 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaActorBlueprint.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORBLUEPRINT_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORBLUEPRINT_H_ + +#include "diagnostic_msgs/msg/KeyValue.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CarlaActorBlueprint_SOURCE) +#define CarlaActorBlueprint_DllAPI __declspec( dllexport ) +#else +#define CarlaActorBlueprint_DllAPI __declspec( dllimport ) +#endif // CarlaActorBlueprint_SOURCE +#else +#define CarlaActorBlueprint_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CarlaActorBlueprint_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace msg { + /*! + * @brief This class represents the structure CarlaActorBlueprint defined by the user in the IDL file. + * @ingroup CARLAACTORBLUEPRINT + */ + class CarlaActorBlueprint + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaActorBlueprint(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaActorBlueprint(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaActorBlueprint that will be copied. + */ + eProsima_user_DllExport CarlaActorBlueprint( + const CarlaActorBlueprint& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaActorBlueprint that will be copied. + */ + eProsima_user_DllExport CarlaActorBlueprint( + CarlaActorBlueprint&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaActorBlueprint that will be copied. + */ + eProsima_user_DllExport CarlaActorBlueprint& operator =( + const CarlaActorBlueprint& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaActorBlueprint that will be copied. + */ + eProsima_user_DllExport CarlaActorBlueprint& operator =( + CarlaActorBlueprint&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaActorBlueprint object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaActorBlueprint& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaActorBlueprint object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaActorBlueprint& x) const; + + /*! + * @brief This function copies the value in member id + * @param _id New value to be copied in member id + */ + eProsima_user_DllExport void id( + const std::string& _id); + + /*! + * @brief This function moves the value in member id + * @param _id New value to be moved in member id + */ + eProsima_user_DllExport void id( + std::string&& _id); + + /*! + * @brief This function returns a constant reference to member id + * @return Constant reference to member id + */ + eProsima_user_DllExport const std::string& id() const; + + /*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ + eProsima_user_DllExport std::string& id(); + /*! + * @brief This function copies the value in member tags + * @param _tags New value to be copied in member tags + */ + eProsima_user_DllExport void tags( + const std::vector& _tags); + + /*! + * @brief This function moves the value in member tags + * @param _tags New value to be moved in member tags + */ + eProsima_user_DllExport void tags( + std::vector&& _tags); + + /*! + * @brief This function returns a constant reference to member tags + * @return Constant reference to member tags + */ + eProsima_user_DllExport const std::vector& tags() const; + + /*! + * @brief This function returns a reference to member tags + * @return Reference to member tags + */ + eProsima_user_DllExport std::vector& tags(); + /*! + * @brief This function copies the value in member attributes + * @param _attributes New value to be copied in member attributes + */ + eProsima_user_DllExport void attributes( + const std::vector& _attributes); + + /*! + * @brief This function moves the value in member attributes + * @param _attributes New value to be moved in member attributes + */ + eProsima_user_DllExport void attributes( + std::vector&& _attributes); + + /*! + * @brief This function returns a constant reference to member attributes + * @return Constant reference to member attributes + */ + eProsima_user_DllExport const std::vector& attributes() const; + + /*! + * @brief This function returns a reference to member attributes + * @return Reference to member attributes + */ + eProsima_user_DllExport std::vector& attributes(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::msg::CarlaActorBlueprint& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std::string m_id; + std::vector m_tags; + std::vector m_attributes; + }; + } // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORBLUEPRINT_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprintPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprintPubSubTypes.cxx new file mode 100644 index 00000000000..cf6a7ea9199 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprintPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaActorBlueprintPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaActorBlueprintPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaActorBlueprintPubSubType::CarlaActorBlueprintPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaActorBlueprint_"); + auto type_size = CarlaActorBlueprint::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaActorBlueprint::isKeyDefined(); + size_t keyLength = CarlaActorBlueprint::getKeyMaxCdrSerializedSize() > 16 ? + CarlaActorBlueprint::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaActorBlueprintPubSubType::~CarlaActorBlueprintPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaActorBlueprintPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaActorBlueprint* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaActorBlueprintPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaActorBlueprint* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaActorBlueprintPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaActorBlueprintPubSubType::createData() + { + return reinterpret_cast(new CarlaActorBlueprint()); + } + + void CarlaActorBlueprintPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaActorBlueprintPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaActorBlueprint* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaActorBlueprint::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaActorBlueprint::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprintPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprintPubSubTypes.h new file mode 100644 index 00000000000..9d5a2a9f4cc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprintPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaActorBlueprintPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORBLUEPRINT_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORBLUEPRINT_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaActorBlueprint.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaActorBlueprint is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CarlaActorBlueprint defined by the user in the IDL file. + * @ingroup CARLAACTORBLUEPRINT + */ + class CarlaActorBlueprintPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaActorBlueprint type; + + eProsima_user_DllExport CarlaActorBlueprintPubSubType(); + + eProsima_user_DllExport virtual ~CarlaActorBlueprintPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORBLUEPRINT_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfo.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfo.cxx new file mode 100644 index 00000000000..7295748ccc0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfo.cxx @@ -0,0 +1,528 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaActorInfo.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaActorInfo.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaActorInfo::CarlaActorInfo() +{ + // m_id com.eprosima.idl.parser.typecode.PrimitiveTypeCode@17c1bced + m_id = 0; + // m_parent_id com.eprosima.idl.parser.typecode.PrimitiveTypeCode@2d9d4f9d + m_parent_id = 0; + // m_type com.eprosima.idl.parser.typecode.StringTypeCode@4034c28c + m_type =""; + // m_rosname com.eprosima.idl.parser.typecode.StringTypeCode@e50a6f6 + m_rosname =""; + // m_rolename com.eprosima.idl.parser.typecode.StringTypeCode@358c99f5 + m_rolename =""; + // m_object_type com.eprosima.idl.parser.typecode.StringTypeCode@3ee0fea4 + m_object_type =""; + // m_base_type com.eprosima.idl.parser.typecode.StringTypeCode@48524010 + m_base_type =""; + // m_topic_prefix com.eprosima.idl.parser.typecode.StringTypeCode@4b168fa9 + m_topic_prefix =""; + +} + +carla_msgs::msg::CarlaActorInfo::~CarlaActorInfo() +{ + + + + + + + +} + +carla_msgs::msg::CarlaActorInfo::CarlaActorInfo( + const CarlaActorInfo& x) +{ + m_id = x.m_id; + m_parent_id = x.m_parent_id; + m_type = x.m_type; + m_rosname = x.m_rosname; + m_rolename = x.m_rolename; + m_object_type = x.m_object_type; + m_base_type = x.m_base_type; + m_topic_prefix = x.m_topic_prefix; +} + +carla_msgs::msg::CarlaActorInfo::CarlaActorInfo( + CarlaActorInfo&& x) +{ + m_id = x.m_id; + m_parent_id = x.m_parent_id; + m_type = std::move(x.m_type); + m_rosname = std::move(x.m_rosname); + m_rolename = std::move(x.m_rolename); + m_object_type = std::move(x.m_object_type); + m_base_type = std::move(x.m_base_type); + m_topic_prefix = std::move(x.m_topic_prefix); +} + +carla_msgs::msg::CarlaActorInfo& carla_msgs::msg::CarlaActorInfo::operator =( + const CarlaActorInfo& x) +{ + + m_id = x.m_id; + m_parent_id = x.m_parent_id; + m_type = x.m_type; + m_rosname = x.m_rosname; + m_rolename = x.m_rolename; + m_object_type = x.m_object_type; + m_base_type = x.m_base_type; + m_topic_prefix = x.m_topic_prefix; + + return *this; +} + +carla_msgs::msg::CarlaActorInfo& carla_msgs::msg::CarlaActorInfo::operator =( + CarlaActorInfo&& x) +{ + + m_id = x.m_id; + m_parent_id = x.m_parent_id; + m_type = std::move(x.m_type); + m_rosname = std::move(x.m_rosname); + m_rolename = std::move(x.m_rolename); + m_object_type = std::move(x.m_object_type); + m_base_type = std::move(x.m_base_type); + m_topic_prefix = std::move(x.m_topic_prefix); + + return *this; +} + +bool carla_msgs::msg::CarlaActorInfo::operator ==( + const CarlaActorInfo& x) const +{ + + return (m_id == x.m_id && m_parent_id == x.m_parent_id && m_type == x.m_type && m_rosname == x.m_rosname && m_rolename == x.m_rolename && m_object_type == x.m_object_type && m_base_type == x.m_base_type && m_topic_prefix == x.m_topic_prefix); +} + +bool carla_msgs::msg::CarlaActorInfo::operator !=( + const CarlaActorInfo& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaActorInfo::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaActorInfo::getCdrSerializedSize( + const carla_msgs::msg::CarlaActorInfo& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.type().size() + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.rosname().size() + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.rolename().size() + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.object_type().size() + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.base_type().size() + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.topic_prefix().size() + 1; + + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaActorInfo::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_id; + scdr << m_parent_id; + scdr << m_type; + scdr << m_rosname; + scdr << m_rolename; + scdr << m_object_type; + scdr << m_base_type; + scdr << m_topic_prefix; + +} + +void carla_msgs::msg::CarlaActorInfo::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_id; + dcdr >> m_parent_id; + dcdr >> m_type; + dcdr >> m_rosname; + dcdr >> m_rolename; + dcdr >> m_object_type; + dcdr >> m_base_type; + dcdr >> m_topic_prefix; +} + +/*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ +void carla_msgs::msg::CarlaActorInfo::id( + uint32_t _id) +{ + m_id = _id; +} + +/*! + * @brief This function returns the value of member id + * @return Value of member id + */ +uint32_t carla_msgs::msg::CarlaActorInfo::id() const +{ + return m_id; +} + +/*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ +uint32_t& carla_msgs::msg::CarlaActorInfo::id() +{ + return m_id; +} + +/*! + * @brief This function sets a value in member parent_id + * @param _parent_id New value for member parent_id + */ +void carla_msgs::msg::CarlaActorInfo::parent_id( + uint32_t _parent_id) +{ + m_parent_id = _parent_id; +} + +/*! + * @brief This function returns the value of member parent_id + * @return Value of member parent_id + */ +uint32_t carla_msgs::msg::CarlaActorInfo::parent_id() const +{ + return m_parent_id; +} + +/*! + * @brief This function returns a reference to member parent_id + * @return Reference to member parent_id + */ +uint32_t& carla_msgs::msg::CarlaActorInfo::parent_id() +{ + return m_parent_id; +} + +/*! + * @brief This function copies the value in member type + * @param _type New value to be copied in member type + */ +void carla_msgs::msg::CarlaActorInfo::type( + const std::string& _type) +{ + m_type = _type; +} + +/*! + * @brief This function moves the value in member type + * @param _type New value to be moved in member type + */ +void carla_msgs::msg::CarlaActorInfo::type( + std::string&& _type) +{ + m_type = std::move(_type); +} + +/*! + * @brief This function returns a constant reference to member type + * @return Constant reference to member type + */ +const std::string& carla_msgs::msg::CarlaActorInfo::type() const +{ + return m_type; +} + +/*! + * @brief This function returns a reference to member type + * @return Reference to member type + */ +std::string& carla_msgs::msg::CarlaActorInfo::type() +{ + return m_type; +} +/*! + * @brief This function copies the value in member rosname + * @param _rosname New value to be copied in member rosname + */ +void carla_msgs::msg::CarlaActorInfo::rosname( + const std::string& _rosname) +{ + m_rosname = _rosname; +} + +/*! + * @brief This function moves the value in member rosname + * @param _rosname New value to be moved in member rosname + */ +void carla_msgs::msg::CarlaActorInfo::rosname( + std::string&& _rosname) +{ + m_rosname = std::move(_rosname); +} + +/*! + * @brief This function returns a constant reference to member rosname + * @return Constant reference to member rosname + */ +const std::string& carla_msgs::msg::CarlaActorInfo::rosname() const +{ + return m_rosname; +} + +/*! + * @brief This function returns a reference to member rosname + * @return Reference to member rosname + */ +std::string& carla_msgs::msg::CarlaActorInfo::rosname() +{ + return m_rosname; +} +/*! + * @brief This function copies the value in member rolename + * @param _rolename New value to be copied in member rolename + */ +void carla_msgs::msg::CarlaActorInfo::rolename( + const std::string& _rolename) +{ + m_rolename = _rolename; +} + +/*! + * @brief This function moves the value in member rolename + * @param _rolename New value to be moved in member rolename + */ +void carla_msgs::msg::CarlaActorInfo::rolename( + std::string&& _rolename) +{ + m_rolename = std::move(_rolename); +} + +/*! + * @brief This function returns a constant reference to member rolename + * @return Constant reference to member rolename + */ +const std::string& carla_msgs::msg::CarlaActorInfo::rolename() const +{ + return m_rolename; +} + +/*! + * @brief This function returns a reference to member rolename + * @return Reference to member rolename + */ +std::string& carla_msgs::msg::CarlaActorInfo::rolename() +{ + return m_rolename; +} +/*! + * @brief This function copies the value in member object_type + * @param _object_type New value to be copied in member object_type + */ +void carla_msgs::msg::CarlaActorInfo::object_type( + const std::string& _object_type) +{ + m_object_type = _object_type; +} + +/*! + * @brief This function moves the value in member object_type + * @param _object_type New value to be moved in member object_type + */ +void carla_msgs::msg::CarlaActorInfo::object_type( + std::string&& _object_type) +{ + m_object_type = std::move(_object_type); +} + +/*! + * @brief This function returns a constant reference to member object_type + * @return Constant reference to member object_type + */ +const std::string& carla_msgs::msg::CarlaActorInfo::object_type() const +{ + return m_object_type; +} + +/*! + * @brief This function returns a reference to member object_type + * @return Reference to member object_type + */ +std::string& carla_msgs::msg::CarlaActorInfo::object_type() +{ + return m_object_type; +} +/*! + * @brief This function copies the value in member base_type + * @param _base_type New value to be copied in member base_type + */ +void carla_msgs::msg::CarlaActorInfo::base_type( + const std::string& _base_type) +{ + m_base_type = _base_type; +} + +/*! + * @brief This function moves the value in member base_type + * @param _base_type New value to be moved in member base_type + */ +void carla_msgs::msg::CarlaActorInfo::base_type( + std::string&& _base_type) +{ + m_base_type = std::move(_base_type); +} + +/*! + * @brief This function returns a constant reference to member base_type + * @return Constant reference to member base_type + */ +const std::string& carla_msgs::msg::CarlaActorInfo::base_type() const +{ + return m_base_type; +} + +/*! + * @brief This function returns a reference to member base_type + * @return Reference to member base_type + */ +std::string& carla_msgs::msg::CarlaActorInfo::base_type() +{ + return m_base_type; +} +/*! + * @brief This function copies the value in member topic_prefix + * @param _topic_prefix New value to be copied in member topic_prefix + */ +void carla_msgs::msg::CarlaActorInfo::topic_prefix( + const std::string& _topic_prefix) +{ + m_topic_prefix = _topic_prefix; +} + +/*! + * @brief This function moves the value in member topic_prefix + * @param _topic_prefix New value to be moved in member topic_prefix + */ +void carla_msgs::msg::CarlaActorInfo::topic_prefix( + std::string&& _topic_prefix) +{ + m_topic_prefix = std::move(_topic_prefix); +} + +/*! + * @brief This function returns a constant reference to member topic_prefix + * @return Constant reference to member topic_prefix + */ +const std::string& carla_msgs::msg::CarlaActorInfo::topic_prefix() const +{ + return m_topic_prefix; +} + +/*! + * @brief This function returns a reference to member topic_prefix + * @return Reference to member topic_prefix + */ +std::string& carla_msgs::msg::CarlaActorInfo::topic_prefix() +{ + return m_topic_prefix; +} + +size_t carla_msgs::msg::CarlaActorInfo::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaActorInfo::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaActorInfo::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfo.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfo.h new file mode 100644 index 00000000000..ec666938ae6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfo.h @@ -0,0 +1,386 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaActorInfo.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORINFO_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORINFO_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CarlaActorInfo_SOURCE) +#define CarlaActorInfo_DllAPI __declspec( dllexport ) +#else +#define CarlaActorInfo_DllAPI __declspec( dllimport ) +#endif // CarlaActorInfo_SOURCE +#else +#define CarlaActorInfo_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CarlaActorInfo_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace msg { + /*! + * @brief This class represents the structure CarlaActorInfo defined by the user in the IDL file. + * @ingroup CARLAACTORINFO + */ + class CarlaActorInfo + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaActorInfo(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaActorInfo(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaActorInfo that will be copied. + */ + eProsima_user_DllExport CarlaActorInfo( + const CarlaActorInfo& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaActorInfo that will be copied. + */ + eProsima_user_DllExport CarlaActorInfo( + CarlaActorInfo&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaActorInfo that will be copied. + */ + eProsima_user_DllExport CarlaActorInfo& operator =( + const CarlaActorInfo& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaActorInfo that will be copied. + */ + eProsima_user_DllExport CarlaActorInfo& operator =( + CarlaActorInfo&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaActorInfo object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaActorInfo& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaActorInfo object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaActorInfo& x) const; + + /*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ + eProsima_user_DllExport void id( + uint32_t _id); + + /*! + * @brief This function returns the value of member id + * @return Value of member id + */ + eProsima_user_DllExport uint32_t id() const; + + /*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ + eProsima_user_DllExport uint32_t& id(); + + /*! + * @brief This function sets a value in member parent_id + * @param _parent_id New value for member parent_id + */ + eProsima_user_DllExport void parent_id( + uint32_t _parent_id); + + /*! + * @brief This function returns the value of member parent_id + * @return Value of member parent_id + */ + eProsima_user_DllExport uint32_t parent_id() const; + + /*! + * @brief This function returns a reference to member parent_id + * @return Reference to member parent_id + */ + eProsima_user_DllExport uint32_t& parent_id(); + + /*! + * @brief This function copies the value in member type + * @param _type New value to be copied in member type + */ + eProsima_user_DllExport void type( + const std::string& _type); + + /*! + * @brief This function moves the value in member type + * @param _type New value to be moved in member type + */ + eProsima_user_DllExport void type( + std::string&& _type); + + /*! + * @brief This function returns a constant reference to member type + * @return Constant reference to member type + */ + eProsima_user_DllExport const std::string& type() const; + + /*! + * @brief This function returns a reference to member type + * @return Reference to member type + */ + eProsima_user_DllExport std::string& type(); + /*! + * @brief This function copies the value in member rosname + * @param _rosname New value to be copied in member rosname + */ + eProsima_user_DllExport void rosname( + const std::string& _rosname); + + /*! + * @brief This function moves the value in member rosname + * @param _rosname New value to be moved in member rosname + */ + eProsima_user_DllExport void rosname( + std::string&& _rosname); + + /*! + * @brief This function returns a constant reference to member rosname + * @return Constant reference to member rosname + */ + eProsima_user_DllExport const std::string& rosname() const; + + /*! + * @brief This function returns a reference to member rosname + * @return Reference to member rosname + */ + eProsima_user_DllExport std::string& rosname(); + /*! + * @brief This function copies the value in member rolename + * @param _rolename New value to be copied in member rolename + */ + eProsima_user_DllExport void rolename( + const std::string& _rolename); + + /*! + * @brief This function moves the value in member rolename + * @param _rolename New value to be moved in member rolename + */ + eProsima_user_DllExport void rolename( + std::string&& _rolename); + + /*! + * @brief This function returns a constant reference to member rolename + * @return Constant reference to member rolename + */ + eProsima_user_DllExport const std::string& rolename() const; + + /*! + * @brief This function returns a reference to member rolename + * @return Reference to member rolename + */ + eProsima_user_DllExport std::string& rolename(); + /*! + * @brief This function copies the value in member object_type + * @param _object_type New value to be copied in member object_type + */ + eProsima_user_DllExport void object_type( + const std::string& _object_type); + + /*! + * @brief This function moves the value in member object_type + * @param _object_type New value to be moved in member object_type + */ + eProsima_user_DllExport void object_type( + std::string&& _object_type); + + /*! + * @brief This function returns a constant reference to member object_type + * @return Constant reference to member object_type + */ + eProsima_user_DllExport const std::string& object_type() const; + + /*! + * @brief This function returns a reference to member object_type + * @return Reference to member object_type + */ + eProsima_user_DllExport std::string& object_type(); + /*! + * @brief This function copies the value in member base_type + * @param _base_type New value to be copied in member base_type + */ + eProsima_user_DllExport void base_type( + const std::string& _base_type); + + /*! + * @brief This function moves the value in member base_type + * @param _base_type New value to be moved in member base_type + */ + eProsima_user_DllExport void base_type( + std::string&& _base_type); + + /*! + * @brief This function returns a constant reference to member base_type + * @return Constant reference to member base_type + */ + eProsima_user_DllExport const std::string& base_type() const; + + /*! + * @brief This function returns a reference to member base_type + * @return Reference to member base_type + */ + eProsima_user_DllExport std::string& base_type(); + /*! + * @brief This function copies the value in member topic_prefix + * @param _topic_prefix New value to be copied in member topic_prefix + */ + eProsima_user_DllExport void topic_prefix( + const std::string& _topic_prefix); + + /*! + * @brief This function moves the value in member topic_prefix + * @param _topic_prefix New value to be moved in member topic_prefix + */ + eProsima_user_DllExport void topic_prefix( + std::string&& _topic_prefix); + + /*! + * @brief This function returns a constant reference to member topic_prefix + * @return Constant reference to member topic_prefix + */ + eProsima_user_DllExport const std::string& topic_prefix() const; + + /*! + * @brief This function returns a reference to member topic_prefix + * @return Reference to member topic_prefix + */ + eProsima_user_DllExport std::string& topic_prefix(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::msg::CarlaActorInfo& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint32_t m_id; + uint32_t m_parent_id; + std::string m_type; + std::string m_rosname; + std::string m_rolename; + std::string m_object_type; + std::string m_base_type; + std::string m_topic_prefix; + }; + } // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORINFO_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfoPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfoPubSubTypes.cxx new file mode 100644 index 00000000000..f3432ecb2df --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfoPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaActorInfoPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaActorInfoPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaActorInfoPubSubType::CarlaActorInfoPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaActorInfo_"); + auto type_size = CarlaActorInfo::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaActorInfo::isKeyDefined(); + size_t keyLength = CarlaActorInfo::getKeyMaxCdrSerializedSize() > 16 ? + CarlaActorInfo::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaActorInfoPubSubType::~CarlaActorInfoPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaActorInfoPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaActorInfo* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaActorInfoPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaActorInfo* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaActorInfoPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaActorInfoPubSubType::createData() + { + return reinterpret_cast(new CarlaActorInfo()); + } + + void CarlaActorInfoPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaActorInfoPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaActorInfo* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaActorInfo::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaActorInfo::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/types/TF2ErrorPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfoPubSubTypes.h similarity index 78% rename from LibCarla/source/carla/ros2/types/TF2ErrorPubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfoPubSubTypes.h index c160a65e4d5..860bfc85ae4 100644 --- a/LibCarla/source/carla/ros2/types/TF2ErrorPubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfoPubSubTypes.h @@ -13,42 +13,43 @@ // limitations under the License. /*! - * @file TF2ErrorPubSubTypes.h + * @file CarlaActorInfoPubSubTypes.h * This header file contains the declaration of the serialization functions. * * This file was generated by the tool fastcdrgen. */ -#ifndef _FAST_DDS_GENERATED_TF2_MSGS_MSG_TF2ERROR_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_TF2_MSGS_MSG_TF2ERROR_PUBSUBTYPES_H_ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORINFO_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORINFO_PUBSUBTYPES_H_ #include #include -#include "TF2Error.h" +#include "CarlaActorInfo.h" #if !defined(GEN_API_VER) || (GEN_API_VER != 1) #error \ - Generated TF2Error is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. + Generated CarlaActorInfo is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. #endif // GEN_API_VER -namespace tf2_msgs +namespace carla_msgs { namespace msg { /*! - * @brief This class represents the TopicDataType of the type TF2Error defined by the user in the IDL file. - * @ingroup TF2ERROR + * @brief This class represents the TopicDataType of the type CarlaActorInfo defined by the user in the IDL file. + * @ingroup CARLAACTORINFO */ - class TF2ErrorPubSubType : public eprosima::fastdds::dds::TopicDataType + class CarlaActorInfoPubSubType : public eprosima::fastdds::dds::TopicDataType { public: - typedef TF2Error type; + typedef CarlaActorInfo type; - eProsima_user_DllExport TF2ErrorPubSubType(); + eProsima_user_DllExport CarlaActorInfoPubSubType(); - eProsima_user_DllExport virtual ~TF2ErrorPubSubType() override; + eProsima_user_DllExport virtual ~CarlaActorInfoPubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -96,10 +97,11 @@ namespace tf2_msgs } #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; unsigned char* m_keyBuffer; }; } } -#endif // _FAST_DDS_GENERATED_TF2_MSGS_MSG_TF2ERROR_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORINFO_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorList.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorList.cxx new file mode 100644 index 00000000000..b917f5d934a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorList.cxx @@ -0,0 +1,198 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaActorList.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaActorList.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaActorList::CarlaActorList() +{ + // m_actors com.eprosima.idl.parser.typecode.SequenceTypeCode@79ca92b9 + + +} + +carla_msgs::msg::CarlaActorList::~CarlaActorList() +{ +} + +carla_msgs::msg::CarlaActorList::CarlaActorList( + const CarlaActorList& x) +{ + m_actors = x.m_actors; +} + +carla_msgs::msg::CarlaActorList::CarlaActorList( + CarlaActorList&& x) +{ + m_actors = std::move(x.m_actors); +} + +carla_msgs::msg::CarlaActorList& carla_msgs::msg::CarlaActorList::operator =( + const CarlaActorList& x) +{ + + m_actors = x.m_actors; + + return *this; +} + +carla_msgs::msg::CarlaActorList& carla_msgs::msg::CarlaActorList::operator =( + CarlaActorList&& x) +{ + + m_actors = std::move(x.m_actors); + + return *this; +} + +bool carla_msgs::msg::CarlaActorList::operator ==( + const CarlaActorList& x) const +{ + + return (m_actors == x.m_actors); +} + +bool carla_msgs::msg::CarlaActorList::operator !=( + const CarlaActorList& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaActorList::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < 100; ++a) + { + current_alignment += carla_msgs::msg::CarlaActorInfo::getMaxCdrSerializedSize(current_alignment);} + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaActorList::getCdrSerializedSize( + const carla_msgs::msg::CarlaActorList& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < data.actors().size(); ++a) + { + current_alignment += carla_msgs::msg::CarlaActorInfo::getCdrSerializedSize(data.actors().at(a), current_alignment);} + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaActorList::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_actors; +} + +void carla_msgs::msg::CarlaActorList::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_actors;} + +/*! + * @brief This function copies the value in member actors + * @param _actors New value to be copied in member actors + */ +void carla_msgs::msg::CarlaActorList::actors( + const std::vector& _actors) +{ + m_actors = _actors; +} + +/*! + * @brief This function moves the value in member actors + * @param _actors New value to be moved in member actors + */ +void carla_msgs::msg::CarlaActorList::actors( + std::vector&& _actors) +{ + m_actors = std::move(_actors); +} + +/*! + * @brief This function returns a constant reference to member actors + * @return Constant reference to member actors + */ +const std::vector& carla_msgs::msg::CarlaActorList::actors() const +{ + return m_actors; +} + +/*! + * @brief This function returns a reference to member actors + * @return Reference to member actors + */ +std::vector& carla_msgs::msg::CarlaActorList::actors() +{ + return m_actors; +} + +size_t carla_msgs::msg::CarlaActorList::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaActorList::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaActorList::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorList.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorList.h new file mode 100644 index 00000000000..ab3e649f07f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorList.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaActorList.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORLIST_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORLIST_H_ + +#include "CarlaActorInfo.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CarlaActorList_SOURCE) +#define CarlaActorList_DllAPI __declspec( dllexport ) +#else +#define CarlaActorList_DllAPI __declspec( dllimport ) +#endif // CarlaActorList_SOURCE +#else +#define CarlaActorList_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CarlaActorList_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace msg { + /*! + * @brief This class represents the structure CarlaActorList defined by the user in the IDL file. + * @ingroup CARLAACTORLIST + */ + class CarlaActorList + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaActorList(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaActorList(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaActorList that will be copied. + */ + eProsima_user_DllExport CarlaActorList( + const CarlaActorList& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaActorList that will be copied. + */ + eProsima_user_DllExport CarlaActorList( + CarlaActorList&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaActorList that will be copied. + */ + eProsima_user_DllExport CarlaActorList& operator =( + const CarlaActorList& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaActorList that will be copied. + */ + eProsima_user_DllExport CarlaActorList& operator =( + CarlaActorList&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaActorList object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaActorList& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaActorList object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaActorList& x) const; + + /*! + * @brief This function copies the value in member actors + * @param _actors New value to be copied in member actors + */ + eProsima_user_DllExport void actors( + const std::vector& _actors); + + /*! + * @brief This function moves the value in member actors + * @param _actors New value to be moved in member actors + */ + eProsima_user_DllExport void actors( + std::vector&& _actors); + + /*! + * @brief This function returns a constant reference to member actors + * @return Constant reference to member actors + */ + eProsima_user_DllExport const std::vector& actors() const; + + /*! + * @brief This function returns a reference to member actors + * @return Reference to member actors + */ + eProsima_user_DllExport std::vector& actors(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::msg::CarlaActorList& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std::vector m_actors; + }; + } // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORLIST_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorListPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorListPubSubTypes.cxx new file mode 100644 index 00000000000..60c088ed9e4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorListPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaActorListPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaActorListPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaActorListPubSubType::CarlaActorListPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaActorList_"); + auto type_size = CarlaActorList::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaActorList::isKeyDefined(); + size_t keyLength = CarlaActorList::getKeyMaxCdrSerializedSize() > 16 ? + CarlaActorList::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaActorListPubSubType::~CarlaActorListPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaActorListPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaActorList* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaActorListPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaActorList* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaActorListPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaActorListPubSubType::createData() + { + return reinterpret_cast(new CarlaActorList()); + } + + void CarlaActorListPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaActorListPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaActorList* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaActorList::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaActorList::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorListPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorListPubSubTypes.h new file mode 100644 index 00000000000..bbaa66ed618 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorListPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaActorListPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORLIST_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORLIST_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaActorList.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaActorList is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CarlaActorList defined by the user in the IDL file. + * @ingroup CARLAACTORLIST + */ + class CarlaActorListPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaActorList type; + + eProsima_user_DllExport CarlaActorListPubSubType(); + + eProsima_user_DllExport virtual ~CarlaActorListPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORLIST_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBox.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBox.cxx new file mode 100644 index 00000000000..b4dbfb25d1f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBox.cxx @@ -0,0 +1,238 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaBoundingBox.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaBoundingBox.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaBoundingBox::CarlaBoundingBox() +{ + // m_center com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@6379eb + + // m_size com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@6379eb + + +} + +carla_msgs::msg::CarlaBoundingBox::~CarlaBoundingBox() +{ + +} + +carla_msgs::msg::CarlaBoundingBox::CarlaBoundingBox( + const CarlaBoundingBox& x) +{ + m_center = x.m_center; + m_size = x.m_size; +} + +carla_msgs::msg::CarlaBoundingBox::CarlaBoundingBox( + CarlaBoundingBox&& x) +{ + m_center = std::move(x.m_center); + m_size = std::move(x.m_size); +} + +carla_msgs::msg::CarlaBoundingBox& carla_msgs::msg::CarlaBoundingBox::operator =( + const CarlaBoundingBox& x) +{ + + m_center = x.m_center; + m_size = x.m_size; + + return *this; +} + +carla_msgs::msg::CarlaBoundingBox& carla_msgs::msg::CarlaBoundingBox::operator =( + CarlaBoundingBox&& x) +{ + + m_center = std::move(x.m_center); + m_size = std::move(x.m_size); + + return *this; +} + +bool carla_msgs::msg::CarlaBoundingBox::operator ==( + const CarlaBoundingBox& x) const +{ + + return (m_center == x.m_center && m_size == x.m_size); +} + +bool carla_msgs::msg::CarlaBoundingBox::operator !=( + const CarlaBoundingBox& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaBoundingBox::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += geometry_msgs::msg::Vector3::getMaxCdrSerializedSize(current_alignment); + current_alignment += geometry_msgs::msg::Vector3::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaBoundingBox::getCdrSerializedSize( + const carla_msgs::msg::CarlaBoundingBox& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += geometry_msgs::msg::Vector3::getCdrSerializedSize(data.center(), current_alignment); + current_alignment += geometry_msgs::msg::Vector3::getCdrSerializedSize(data.size(), current_alignment); + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaBoundingBox::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_center; + scdr << m_size; + +} + +void carla_msgs::msg::CarlaBoundingBox::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_center; + dcdr >> m_size; +} + +/*! + * @brief This function copies the value in member center + * @param _center New value to be copied in member center + */ +void carla_msgs::msg::CarlaBoundingBox::center( + const geometry_msgs::msg::Vector3& _center) +{ + m_center = _center; +} + +/*! + * @brief This function moves the value in member center + * @param _center New value to be moved in member center + */ +void carla_msgs::msg::CarlaBoundingBox::center( + geometry_msgs::msg::Vector3&& _center) +{ + m_center = std::move(_center); +} + +/*! + * @brief This function returns a constant reference to member center + * @return Constant reference to member center + */ +const geometry_msgs::msg::Vector3& carla_msgs::msg::CarlaBoundingBox::center() const +{ + return m_center; +} + +/*! + * @brief This function returns a reference to member center + * @return Reference to member center + */ +geometry_msgs::msg::Vector3& carla_msgs::msg::CarlaBoundingBox::center() +{ + return m_center; +} +/*! + * @brief This function copies the value in member size + * @param _size New value to be copied in member size + */ +void carla_msgs::msg::CarlaBoundingBox::size( + const geometry_msgs::msg::Vector3& _size) +{ + m_size = _size; +} + +/*! + * @brief This function moves the value in member size + * @param _size New value to be moved in member size + */ +void carla_msgs::msg::CarlaBoundingBox::size( + geometry_msgs::msg::Vector3&& _size) +{ + m_size = std::move(_size); +} + +/*! + * @brief This function returns a constant reference to member size + * @return Constant reference to member size + */ +const geometry_msgs::msg::Vector3& carla_msgs::msg::CarlaBoundingBox::size() const +{ + return m_size; +} + +/*! + * @brief This function returns a reference to member size + * @return Reference to member size + */ +geometry_msgs::msg::Vector3& carla_msgs::msg::CarlaBoundingBox::size() +{ + return m_size; +} + +size_t carla_msgs::msg::CarlaBoundingBox::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaBoundingBox::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaBoundingBox::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBox.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBox.h new file mode 100644 index 00000000000..5ab9197c590 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBox.h @@ -0,0 +1,243 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaBoundingBox.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLABOUNDINGBOX_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLABOUNDINGBOX_H_ + +#include "geometry_msgs/msg/Vector3.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CarlaBoundingBox_SOURCE) +#define CarlaBoundingBox_DllAPI __declspec( dllexport ) +#else +#define CarlaBoundingBox_DllAPI __declspec( dllimport ) +#endif // CarlaBoundingBox_SOURCE +#else +#define CarlaBoundingBox_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CarlaBoundingBox_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace msg { + /*! + * @brief This class represents the structure CarlaBoundingBox defined by the user in the IDL file. + * @ingroup CARLABOUNDINGBOX + */ + class CarlaBoundingBox + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaBoundingBox(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaBoundingBox(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaBoundingBox that will be copied. + */ + eProsima_user_DllExport CarlaBoundingBox( + const CarlaBoundingBox& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaBoundingBox that will be copied. + */ + eProsima_user_DllExport CarlaBoundingBox( + CarlaBoundingBox&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaBoundingBox that will be copied. + */ + eProsima_user_DllExport CarlaBoundingBox& operator =( + const CarlaBoundingBox& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaBoundingBox that will be copied. + */ + eProsima_user_DllExport CarlaBoundingBox& operator =( + CarlaBoundingBox&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaBoundingBox object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaBoundingBox& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaBoundingBox object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaBoundingBox& x) const; + + /*! + * @brief This function copies the value in member center + * @param _center New value to be copied in member center + */ + eProsima_user_DllExport void center( + const geometry_msgs::msg::Vector3& _center); + + /*! + * @brief This function moves the value in member center + * @param _center New value to be moved in member center + */ + eProsima_user_DllExport void center( + geometry_msgs::msg::Vector3&& _center); + + /*! + * @brief This function returns a constant reference to member center + * @return Constant reference to member center + */ + eProsima_user_DllExport const geometry_msgs::msg::Vector3& center() const; + + /*! + * @brief This function returns a reference to member center + * @return Reference to member center + */ + eProsima_user_DllExport geometry_msgs::msg::Vector3& center(); + /*! + * @brief This function copies the value in member size + * @param _size New value to be copied in member size + */ + eProsima_user_DllExport void size( + const geometry_msgs::msg::Vector3& _size); + + /*! + * @brief This function moves the value in member size + * @param _size New value to be moved in member size + */ + eProsima_user_DllExport void size( + geometry_msgs::msg::Vector3&& _size); + + /*! + * @brief This function returns a constant reference to member size + * @return Constant reference to member size + */ + eProsima_user_DllExport const geometry_msgs::msg::Vector3& size() const; + + /*! + * @brief This function returns a reference to member size + * @return Reference to member size + */ + eProsima_user_DllExport geometry_msgs::msg::Vector3& size(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::msg::CarlaBoundingBox& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + geometry_msgs::msg::Vector3 m_center; + geometry_msgs::msg::Vector3 m_size; + }; + } // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLABOUNDINGBOX_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBoxPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBoxPubSubTypes.cxx new file mode 100644 index 00000000000..835b49206f3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBoxPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaBoundingBoxPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaBoundingBoxPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaBoundingBoxPubSubType::CarlaBoundingBoxPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaBoundingBox_"); + auto type_size = CarlaBoundingBox::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaBoundingBox::isKeyDefined(); + size_t keyLength = CarlaBoundingBox::getKeyMaxCdrSerializedSize() > 16 ? + CarlaBoundingBox::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaBoundingBoxPubSubType::~CarlaBoundingBoxPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaBoundingBoxPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaBoundingBox* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaBoundingBoxPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaBoundingBox* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaBoundingBoxPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaBoundingBoxPubSubType::createData() + { + return reinterpret_cast(new CarlaBoundingBox()); + } + + void CarlaBoundingBoxPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaBoundingBoxPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaBoundingBox* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaBoundingBox::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaBoundingBox::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBoxPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBoxPubSubTypes.h new file mode 100644 index 00000000000..6be65c2a042 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBoxPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaBoundingBoxPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLABOUNDINGBOX_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLABOUNDINGBOX_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaBoundingBox.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaBoundingBox is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CarlaBoundingBox defined by the user in the IDL file. + * @ingroup CARLABOUNDINGBOX + */ + class CarlaBoundingBoxPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaBoundingBox type; + + eProsima_user_DllExport CarlaBoundingBoxPubSubType(); + + eProsima_user_DllExport virtual ~CarlaBoundingBoxPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) CarlaBoundingBox(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLABOUNDINGBOX_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/CarlaCollisionEvent.cpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEvent.cxx similarity index 86% rename from LibCarla/source/carla/ros2/types/CarlaCollisionEvent.cpp rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEvent.cxx index 4d01b7d78f8..6a71c72d358 100644 --- a/LibCarla/source/carla/ros2/types/CarlaCollisionEvent.cpp +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEvent.cxx @@ -13,7 +13,7 @@ // limitations under the License. /*! - * @file CarlaCarlaCollisionEvent.cpp + * @file CarlaCollisionEvent.cpp * This source file contains the definition of the described types in the IDL file. * * This file was generated by the tool gen. @@ -34,25 +34,21 @@ using namespace eprosima::fastcdr::exception; #include -#define carla_msgs_msg_geometry_msgs_msg_Vector3_max_cdr_typesize 24ULL; -#define carla_msgs_msg_std_msgs_msg_Header_max_cdr_typesize 268ULL; -#define carla_msgs_msg_CarlaCollisionEvent_max_cdr_typesize 296ULL; -#define carla_msgs_msg_std_msgs_msg_Time_max_cdr_typesize 8ULL; -#define carla_msgs_msg_geometry_msgs_msg_Vector3_max_key_cdr_typesize 0ULL; -#define carla_msgs_msg_std_msgs_msg_Header_max_key_cdr_typesize 0ULL; -#define carla_msgs_msg_CarlaCollisionEvent_max_key_cdr_typesize 0ULL; -#define carla_msgs_msg_std_msgs_msg_Time_max_key_cdr_typesize 0ULL; - carla_msgs::msg::CarlaCollisionEvent::CarlaCollisionEvent() { - // std_msgs::msg::Header m_header - // unsigned long m_other_actor_id + // m_header com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@31f9b85e + + // m_other_actor_id com.eprosima.idl.parser.typecode.PrimitiveTypeCode@424e1977 m_other_actor_id = 0; - // geometry_msgs::msg::Vector3 m_normal_impulse + // m_normal_impulse com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@10d68fcd + + } carla_msgs::msg::CarlaCollisionEvent::~CarlaCollisionEvent() { + + } carla_msgs::msg::CarlaCollisionEvent::CarlaCollisionEvent( @@ -64,7 +60,7 @@ carla_msgs::msg::CarlaCollisionEvent::CarlaCollisionEvent( } carla_msgs::msg::CarlaCollisionEvent::CarlaCollisionEvent( - CarlaCollisionEvent&& x) noexcept + CarlaCollisionEvent&& x) { m_header = std::move(x.m_header); m_other_actor_id = x.m_other_actor_id; @@ -74,6 +70,7 @@ carla_msgs::msg::CarlaCollisionEvent::CarlaCollisionEvent( carla_msgs::msg::CarlaCollisionEvent& carla_msgs::msg::CarlaCollisionEvent::operator =( const CarlaCollisionEvent& x) { + m_header = x.m_header; m_other_actor_id = x.m_other_actor_id; m_normal_impulse = x.m_normal_impulse; @@ -82,8 +79,9 @@ carla_msgs::msg::CarlaCollisionEvent& carla_msgs::msg::CarlaCollisionEvent::oper } carla_msgs::msg::CarlaCollisionEvent& carla_msgs::msg::CarlaCollisionEvent::operator =( - CarlaCollisionEvent&& x) noexcept + CarlaCollisionEvent&& x) { + m_header = std::move(x.m_header); m_other_actor_id = x.m_other_actor_id; m_normal_impulse = std::move(x.m_normal_impulse); @@ -94,6 +92,7 @@ carla_msgs::msg::CarlaCollisionEvent& carla_msgs::msg::CarlaCollisionEvent::oper bool carla_msgs::msg::CarlaCollisionEvent::operator ==( const CarlaCollisionEvent& x) const { + return (m_header == x.m_header && m_other_actor_id == x.m_other_actor_id && m_normal_impulse == x.m_normal_impulse); } @@ -106,8 +105,16 @@ bool carla_msgs::msg::CarlaCollisionEvent::operator !=( size_t carla_msgs::msg::CarlaCollisionEvent::getMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return carla_msgs_msg_CarlaCollisionEvent_max_cdr_typesize; + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getMaxCdrSerializedSize(current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += geometry_msgs::msg::Vector3::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; } size_t carla_msgs::msg::CarlaCollisionEvent::getCdrSerializedSize( @@ -116,23 +123,31 @@ size_t carla_msgs::msg::CarlaCollisionEvent::getCdrSerializedSize( { (void)data; size_t initial_alignment = current_alignment; + + current_alignment += std_msgs::msg::Header::getCdrSerializedSize(data.header(), current_alignment); current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + current_alignment += geometry_msgs::msg::Vector3::getCdrSerializedSize(data.normal_impulse(), current_alignment); + return current_alignment - initial_alignment; } void carla_msgs::msg::CarlaCollisionEvent::serialize( eprosima::fastcdr::Cdr& scdr) const { + scdr << m_header; scdr << m_other_actor_id; scdr << m_normal_impulse; + } void carla_msgs::msg::CarlaCollisionEvent::deserialize( eprosima::fastcdr::Cdr& dcdr) { + dcdr >> m_header; dcdr >> m_other_actor_id; dcdr >> m_normal_impulse; @@ -175,7 +190,6 @@ std_msgs::msg::Header& carla_msgs::msg::CarlaCollisionEvent::header() { return m_header; } - /*! * @brief This function sets a value in member other_actor_id * @param _other_actor_id New value for member other_actor_id @@ -245,8 +259,11 @@ geometry_msgs::msg::Vector3& carla_msgs::msg::CarlaCollisionEvent::normal_impuls size_t carla_msgs::msg::CarlaCollisionEvent::getKeyMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return carla_msgs_msg_CarlaCollisionEvent_max_key_cdr_typesize; + size_t current_align = current_alignment; + + + + return current_align; } bool carla_msgs::msg::CarlaCollisionEvent::isKeyDefined() @@ -258,4 +275,7 @@ void carla_msgs::msg::CarlaCollisionEvent::serializeKey( eprosima::fastcdr::Cdr& scdr) const { (void) scdr; + } + + diff --git a/LibCarla/source/carla/ros2/types/CarlaCollisionEvent.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEvent.h similarity index 95% rename from LibCarla/source/carla/ros2/types/CarlaCollisionEvent.h rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEvent.h index 6aacc077a70..70b1234f7ce 100644 --- a/LibCarla/source/carla/ros2/types/CarlaCollisionEvent.h +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEvent.h @@ -22,10 +22,8 @@ #ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENT_H_ #define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENT_H_ -#include "Vector3.h" -#include "Header.h" - -#include +#include "geometry_msgs/msg/Vector3.h" +#include "std_msgs/msg/Header.h" #include #include @@ -97,7 +95,7 @@ namespace carla_msgs { * @param x Reference to the object carla_msgs::msg::CarlaCollisionEvent that will be copied. */ eProsima_user_DllExport CarlaCollisionEvent( - CarlaCollisionEvent&& x) noexcept; + CarlaCollisionEvent&& x); /*! * @brief Copy assignment. @@ -111,7 +109,7 @@ namespace carla_msgs { * @param x Reference to the object carla_msgs::msg::CarlaCollisionEvent that will be copied. */ eProsima_user_DllExport CarlaCollisionEvent& operator =( - CarlaCollisionEvent&& x) noexcept; + CarlaCollisionEvent&& x); /*! * @brief Comparison operator. @@ -198,11 +196,11 @@ namespace carla_msgs { eProsima_user_DllExport geometry_msgs::msg::Vector3& normal_impulse(); /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -216,6 +214,7 @@ namespace carla_msgs { const carla_msgs::msg::CarlaCollisionEvent& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -230,6 +229,8 @@ namespace carla_msgs { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -252,6 +253,7 @@ namespace carla_msgs { eprosima::fastcdr::Cdr& cdr) const; private: + std_msgs::msg::Header m_header; uint32_t m_other_actor_id; geometry_msgs::msg::Vector3 m_normal_impulse; @@ -259,4 +261,4 @@ namespace carla_msgs { } // namespace msg } // namespace carla_msgs -#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENT_H_ +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENT_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/CarlaCollisionEventPubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEventPubSubTypes.cxx similarity index 89% rename from LibCarla/source/carla/ros2/types/CarlaCollisionEventPubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEventPubSubTypes.cxx index c1822eb2b68..3b3d04904d3 100644 --- a/LibCarla/source/carla/ros2/types/CarlaCollisionEventPubSubTypes.cpp +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEventPubSubTypes.cxx @@ -19,6 +19,7 @@ * This file was generated by the tool fastcdrgen. */ + #include #include @@ -83,21 +84,21 @@ namespace carla_msgs { SerializedPayload_t* payload, void* data) { - try - { - //Convert DATA to pointer of your type - CarlaCollisionEvent* p_type = static_cast(data); + //Convert DATA to pointer of your type + CarlaCollisionEvent* p_type = static_cast(data); - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); - // Deserialize encapsulation. - deser.read_encapsulation(); - payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + try + { // Deserialize the object. p_type->deserialize(deser); } @@ -168,5 +169,8 @@ namespace carla_msgs { } return true; } + + } //End of namespace msg + } //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/types/CarlaCollisionEventPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEventPubSubTypes.h similarity index 97% rename from LibCarla/source/carla/ros2/types/CarlaCollisionEventPubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEventPubSubTypes.h index d532d8e851e..7bce83aedc7 100644 --- a/LibCarla/source/carla/ros2/types/CarlaCollisionEventPubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEventPubSubTypes.h @@ -27,8 +27,6 @@ #include #include "CarlaCollisionEvent.h" -#include "Vector3PubSubTypes.h" -#include "HeaderPubSubTypes.h" #if !defined(GEN_API_VER) || (GEN_API_VER != 1) #error \ @@ -39,7 +37,6 @@ namespace carla_msgs { namespace msg { - /*! * @brief This class represents the TopicDataType of the type CarlaCollisionEvent defined by the user in the IDL file. * @ingroup CARLACOLLISIONEVENT @@ -52,7 +49,7 @@ namespace carla_msgs eProsima_user_DllExport CarlaCollisionEventPubSubType(); - eProsima_user_DllExport virtual ~CarlaCollisionEventPubSubType() override; + eProsima_user_DllExport virtual ~CarlaCollisionEventPubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -103,9 +100,8 @@ namespace carla_msgs MD5 m_md5; unsigned char* m_keyBuffer; - }; } } -#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENT_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENT_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControl.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControl.cxx new file mode 100644 index 00000000000..f3be268c5ef --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControl.cxx @@ -0,0 +1,187 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaControl.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaControl.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + +carla_msgs::msg::CarlaControl::CarlaControl() +{ + // m_command com.eprosima.idl.parser.typecode.PrimitiveTypeCode@11c9af63 + m_command = 0; + +} + +carla_msgs::msg::CarlaControl::~CarlaControl() +{ +} + +carla_msgs::msg::CarlaControl::CarlaControl( + const CarlaControl& x) +{ + m_command = x.m_command; +} + +carla_msgs::msg::CarlaControl::CarlaControl( + CarlaControl&& x) +{ + m_command = x.m_command; +} + +carla_msgs::msg::CarlaControl& carla_msgs::msg::CarlaControl::operator =( + const CarlaControl& x) +{ + + m_command = x.m_command; + + return *this; +} + +carla_msgs::msg::CarlaControl& carla_msgs::msg::CarlaControl::operator =( + CarlaControl&& x) +{ + + m_command = x.m_command; + + return *this; +} + +bool carla_msgs::msg::CarlaControl::operator ==( + const CarlaControl& x) const +{ + + return (m_command == x.m_command); +} + +bool carla_msgs::msg::CarlaControl::operator !=( + const CarlaControl& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaControl::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaControl::getCdrSerializedSize( + const carla_msgs::msg::CarlaControl& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaControl::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_command; + +} + +void carla_msgs::msg::CarlaControl::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_command; +} + +/*! + * @brief This function sets a value in member command + * @param _command New value for member command + */ +void carla_msgs::msg::CarlaControl::command( + int8_t _command) +{ + m_command = _command; +} + +/*! + * @brief This function returns the value of member command + * @return Value of member command + */ +int8_t carla_msgs::msg::CarlaControl::command() const +{ + return m_command; +} + +/*! + * @brief This function returns a reference to member command + * @return Reference to member command + */ +int8_t& carla_msgs::msg::CarlaControl::command() +{ + return m_command; +} + + +size_t carla_msgs::msg::CarlaControl::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaControl::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaControl::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/types/Clock.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControl.h similarity index 60% rename from LibCarla/source/carla/ros2/types/Clock.h rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControl.h index 862b8193f49..807600956f5 100644 --- a/LibCarla/source/carla/ros2/types/Clock.h +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControl.h @@ -13,18 +13,15 @@ // limitations under the License. /*! - * @file Clock.h + * @file CarlaControl.h * This header file contains the declaration of the described types in the IDL file. * * This file was generated by the tool gen. */ -#ifndef _FAST_DDS_GENERATED_ROSGRAPH_MSG_CLOCK_H_ -#define _FAST_DDS_GENERATED_ROSGRAPH_MSG_CLOCK_H_ +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACONTROL_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACONTROL_H_ -#include "Time.h" - -#include #include #include @@ -45,16 +42,16 @@ #if defined(_WIN32) #if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(CLOCK_SOURCE) -#define CLOCK_DllAPI __declspec( dllexport ) +#if defined(CarlaControl_SOURCE) +#define CarlaControl_DllAPI __declspec( dllexport ) #else -#define CLOCK_DllAPI __declspec( dllimport ) -#endif // CLOCK_SOURCE +#define CarlaControl_DllAPI __declspec( dllimport ) +#endif // CarlaControl_SOURCE #else -#define CLOCK_DllAPI +#define CarlaControl_DllAPI #endif // EPROSIMA_USER_DLL_EXPORT #else -#define CLOCK_DllAPI +#define CarlaControl_DllAPI #endif // _WIN32 namespace eprosima { @@ -63,100 +60,100 @@ class Cdr; } // namespace fastcdr } // namespace eprosima -namespace rosgraph { + +namespace carla_msgs { namespace msg { + namespace CarlaControl_Constants { + const int8_t PLAY = 0; + const int8_t PAUSE = 1; + const int8_t STEP_ONCE = 2; + } // namespace CarlaControl_Constants /*! - * @brief This class represents the structure Clock defined by the user in the IDL file. - * @ingroup Clock + * @brief This class represents the structure CarlaControl defined by the user in the IDL file. + * @ingroup CARLACONTROL */ - class Clock + class CarlaControl { public: /*! * @brief Default constructor. */ - eProsima_user_DllExport Clock(); + eProsima_user_DllExport CarlaControl(); /*! * @brief Default destructor. */ - eProsima_user_DllExport ~Clock(); + eProsima_user_DllExport ~CarlaControl(); /*! * @brief Copy constructor. - * @param x Reference to the object rosgraph::msg::Clock that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaControl that will be copied. */ - eProsima_user_DllExport Clock( - const Clock& x); + eProsima_user_DllExport CarlaControl( + const CarlaControl& x); /*! * @brief Move constructor. - * @param x Reference to the object rosgraph::msg::Clock that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaControl that will be copied. */ - eProsima_user_DllExport Clock( - Clock&& x) noexcept; + eProsima_user_DllExport CarlaControl( + CarlaControl&& x); /*! * @brief Copy assignment. - * @param x Reference to the object rosgraph::msg::Clock that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaControl that will be copied. */ - eProsima_user_DllExport Clock& operator =( - const Clock& x); + eProsima_user_DllExport CarlaControl& operator =( + const CarlaControl& x); /*! * @brief Move assignment. - * @param x Reference to the object rosgraph::msg::Clock that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaControl that will be copied. */ - eProsima_user_DllExport Clock& operator =( - Clock&& x) noexcept; + eProsima_user_DllExport CarlaControl& operator =( + CarlaControl&& x); /*! * @brief Comparison operator. - * @param x rosgraph::msg::Clock object to compare. + * @param x carla_msgs::msg::CarlaControl object to compare. */ eProsima_user_DllExport bool operator ==( - const Clock& x) const; + const CarlaControl& x) const; /*! * @brief Comparison operator. - * @param x rosgraph::msg::Clock object to compare. + * @param x carla_msgs::msg::CarlaControl object to compare. */ eProsima_user_DllExport bool operator !=( - const Clock& x) const; + const CarlaControl& x) const; /*! - * @brief This function copies the value in member clock - * @param _clock New value to be copied in member clock + * @brief This function sets a value in member command + * @param _command New value for member command */ - eProsima_user_DllExport void clock( - const builtin_interfaces::msg::Time& _clock); + eProsima_user_DllExport void command( + int8_t _command); /*! - * @brief This function moves the value in member clock - * @param _clock New value to be moved in member clock + * @brief This function returns the value of member command + * @return Value of member command */ - eProsima_user_DllExport void clock( - builtin_interfaces::msg::Time&& _clock); + eProsima_user_DllExport int8_t command() const; /*! - * @brief This function returns a constant reference to member clock - * @return Constant reference to member clock + * @brief This function returns a reference to member command + * @return Reference to member command */ - eProsima_user_DllExport const builtin_interfaces::msg::Time& clock() const; + eProsima_user_DllExport int8_t& command(); - /*! - * @brief This function returns a reference to member clock - * @return Reference to member clock - */ - eProsima_user_DllExport builtin_interfaces::msg::Time& clock(); /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -167,9 +164,10 @@ namespace rosgraph { * @return Serialized size. */ eProsima_user_DllExport static size_t getCdrSerializedSize( - const rosgraph::msg::Clock& data, + const carla_msgs::msg::CarlaControl& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -184,6 +182,8 @@ namespace rosgraph { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -206,9 +206,10 @@ namespace rosgraph { eprosima::fastcdr::Cdr& cdr) const; private: - builtin_interfaces::msg::Time m_clock; + + int8_t m_command; }; } // namespace msg -} // namespace rosgraph +} // namespace carla_msgs -#endif // _FAST_DDS_GENERATED_ROSGRAPH_MSG_CLOCK_H_ +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACONTROL_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControlPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControlPubSubTypes.cxx new file mode 100644 index 00000000000..952965abb37 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControlPubSubTypes.cxx @@ -0,0 +1,182 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaControlPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaControlPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + namespace CarlaControl_Constants { + + + + + } //End of namespace CarlaControl_Constants + CarlaControlPubSubType::CarlaControlPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaControl_"); + auto type_size = CarlaControl::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaControl::isKeyDefined(); + size_t keyLength = CarlaControl::getKeyMaxCdrSerializedSize() > 16 ? + CarlaControl::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaControlPubSubType::~CarlaControlPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaControlPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaControl* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaControlPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaControl* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaControlPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaControlPubSubType::createData() + { + return reinterpret_cast(new CarlaControl()); + } + + void CarlaControlPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaControlPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaControl* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaControl::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaControl::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControlPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControlPubSubTypes.h new file mode 100644 index 00000000000..a26ea9f1605 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControlPubSubTypes.h @@ -0,0 +1,113 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaControlPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACONTROL_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACONTROL_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaControl.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaControl is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + namespace CarlaControl_Constants + { + + + + } + /*! + * @brief This class represents the TopicDataType of the type CarlaControl defined by the user in the IDL file. + * @ingroup CARLACONTROL + */ + class CarlaControlPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaControl type; + + eProsima_user_DllExport CarlaControlPubSubType(); + + eProsima_user_DllExport virtual ~CarlaControlPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) CarlaControl(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACONTROL_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettings.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettings.cxx new file mode 100644 index 00000000000..bb6e9dcfec3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettings.cxx @@ -0,0 +1,615 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaEpisodeSettings.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaEpisodeSettings.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaEpisodeSettings::CarlaEpisodeSettings() +{ + // m_synchronous_mode com.eprosima.idl.parser.typecode.PrimitiveTypeCode@68e965f5 + m_synchronous_mode = false; + // m_no_rendering_mode com.eprosima.idl.parser.typecode.PrimitiveTypeCode@6f27a732 + m_no_rendering_mode = false; + // m_fixed_delta_seconds com.eprosima.idl.parser.typecode.PrimitiveTypeCode@6c779568 + m_fixed_delta_seconds = 0.0; + // m_substepping com.eprosima.idl.parser.typecode.PrimitiveTypeCode@f381794 + m_substepping = true; + // m_max_substep_delta_time com.eprosima.idl.parser.typecode.PrimitiveTypeCode@2cdd0d4b + m_max_substep_delta_time = 0.01; + // m_max_substeps com.eprosima.idl.parser.typecode.PrimitiveTypeCode@61d6015a + m_max_substeps = 10; + // m_max_culling_distance com.eprosima.idl.parser.typecode.PrimitiveTypeCode@2525ff7e + m_max_culling_distance = 0.0; + // m_deterministic_ragdolls com.eprosima.idl.parser.typecode.PrimitiveTypeCode@524d6d96 + m_deterministic_ragdolls = false; + // m_tile_stream_distance com.eprosima.idl.parser.typecode.PrimitiveTypeCode@152aa092 + m_tile_stream_distance = 3000.0; + // m_actor_active_distance com.eprosima.idl.parser.typecode.PrimitiveTypeCode@44a7bfbc + m_actor_active_distance = 2000.0; + // m_spectator_as_ego com.eprosima.idl.parser.typecode.PrimitiveTypeCode@4ef37659 + m_spectator_as_ego = true; + +} + +carla_msgs::msg::CarlaEpisodeSettings::~CarlaEpisodeSettings() +{ + + + + + + + + + + +} + +carla_msgs::msg::CarlaEpisodeSettings::CarlaEpisodeSettings( + const CarlaEpisodeSettings& x) +{ + m_synchronous_mode = x.m_synchronous_mode; + m_no_rendering_mode = x.m_no_rendering_mode; + m_fixed_delta_seconds = x.m_fixed_delta_seconds; + m_substepping = x.m_substepping; + m_max_substep_delta_time = x.m_max_substep_delta_time; + m_max_substeps = x.m_max_substeps; + m_max_culling_distance = x.m_max_culling_distance; + m_deterministic_ragdolls = x.m_deterministic_ragdolls; + m_tile_stream_distance = x.m_tile_stream_distance; + m_actor_active_distance = x.m_actor_active_distance; + m_spectator_as_ego = x.m_spectator_as_ego; +} + +carla_msgs::msg::CarlaEpisodeSettings::CarlaEpisodeSettings( + CarlaEpisodeSettings&& x) +{ + m_synchronous_mode = x.m_synchronous_mode; + m_no_rendering_mode = x.m_no_rendering_mode; + m_fixed_delta_seconds = x.m_fixed_delta_seconds; + m_substepping = x.m_substepping; + m_max_substep_delta_time = x.m_max_substep_delta_time; + m_max_substeps = x.m_max_substeps; + m_max_culling_distance = x.m_max_culling_distance; + m_deterministic_ragdolls = x.m_deterministic_ragdolls; + m_tile_stream_distance = x.m_tile_stream_distance; + m_actor_active_distance = x.m_actor_active_distance; + m_spectator_as_ego = x.m_spectator_as_ego; +} + +carla_msgs::msg::CarlaEpisodeSettings& carla_msgs::msg::CarlaEpisodeSettings::operator =( + const CarlaEpisodeSettings& x) +{ + + m_synchronous_mode = x.m_synchronous_mode; + m_no_rendering_mode = x.m_no_rendering_mode; + m_fixed_delta_seconds = x.m_fixed_delta_seconds; + m_substepping = x.m_substepping; + m_max_substep_delta_time = x.m_max_substep_delta_time; + m_max_substeps = x.m_max_substeps; + m_max_culling_distance = x.m_max_culling_distance; + m_deterministic_ragdolls = x.m_deterministic_ragdolls; + m_tile_stream_distance = x.m_tile_stream_distance; + m_actor_active_distance = x.m_actor_active_distance; + m_spectator_as_ego = x.m_spectator_as_ego; + + return *this; +} + +carla_msgs::msg::CarlaEpisodeSettings& carla_msgs::msg::CarlaEpisodeSettings::operator =( + CarlaEpisodeSettings&& x) +{ + + m_synchronous_mode = x.m_synchronous_mode; + m_no_rendering_mode = x.m_no_rendering_mode; + m_fixed_delta_seconds = x.m_fixed_delta_seconds; + m_substepping = x.m_substepping; + m_max_substep_delta_time = x.m_max_substep_delta_time; + m_max_substeps = x.m_max_substeps; + m_max_culling_distance = x.m_max_culling_distance; + m_deterministic_ragdolls = x.m_deterministic_ragdolls; + m_tile_stream_distance = x.m_tile_stream_distance; + m_actor_active_distance = x.m_actor_active_distance; + m_spectator_as_ego = x.m_spectator_as_ego; + + return *this; +} + +bool carla_msgs::msg::CarlaEpisodeSettings::operator ==( + const CarlaEpisodeSettings& x) const +{ + + return (m_synchronous_mode == x.m_synchronous_mode && m_no_rendering_mode == x.m_no_rendering_mode && m_fixed_delta_seconds == x.m_fixed_delta_seconds && m_substepping == x.m_substepping && m_max_substep_delta_time == x.m_max_substep_delta_time && m_max_substeps == x.m_max_substeps && m_max_culling_distance == x.m_max_culling_distance && m_deterministic_ragdolls == x.m_deterministic_ragdolls && m_tile_stream_distance == x.m_tile_stream_distance && m_actor_active_distance == x.m_actor_active_distance && m_spectator_as_ego == x.m_spectator_as_ego); +} + +bool carla_msgs::msg::CarlaEpisodeSettings::operator !=( + const CarlaEpisodeSettings& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaEpisodeSettings::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaEpisodeSettings::getCdrSerializedSize( + const carla_msgs::msg::CarlaEpisodeSettings& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaEpisodeSettings::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_synchronous_mode; + scdr << m_no_rendering_mode; + scdr << m_fixed_delta_seconds; + scdr << m_substepping; + scdr << m_max_substep_delta_time; + scdr << m_max_substeps; + scdr << m_max_culling_distance; + scdr << m_deterministic_ragdolls; + scdr << m_tile_stream_distance; + scdr << m_actor_active_distance; + scdr << m_spectator_as_ego; + +} + +void carla_msgs::msg::CarlaEpisodeSettings::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_synchronous_mode; + dcdr >> m_no_rendering_mode; + dcdr >> m_fixed_delta_seconds; + dcdr >> m_substepping; + dcdr >> m_max_substep_delta_time; + dcdr >> m_max_substeps; + dcdr >> m_max_culling_distance; + dcdr >> m_deterministic_ragdolls; + dcdr >> m_tile_stream_distance; + dcdr >> m_actor_active_distance; + dcdr >> m_spectator_as_ego; +} + +/*! + * @brief This function sets a value in member synchronous_mode + * @param _synchronous_mode New value for member synchronous_mode + */ +void carla_msgs::msg::CarlaEpisodeSettings::synchronous_mode( + bool _synchronous_mode) +{ + m_synchronous_mode = _synchronous_mode; +} + +/*! + * @brief This function returns the value of member synchronous_mode + * @return Value of member synchronous_mode + */ +bool carla_msgs::msg::CarlaEpisodeSettings::synchronous_mode() const +{ + return m_synchronous_mode; +} + +/*! + * @brief This function returns a reference to member synchronous_mode + * @return Reference to member synchronous_mode + */ +bool& carla_msgs::msg::CarlaEpisodeSettings::synchronous_mode() +{ + return m_synchronous_mode; +} + +/*! + * @brief This function sets a value in member no_rendering_mode + * @param _no_rendering_mode New value for member no_rendering_mode + */ +void carla_msgs::msg::CarlaEpisodeSettings::no_rendering_mode( + bool _no_rendering_mode) +{ + m_no_rendering_mode = _no_rendering_mode; +} + +/*! + * @brief This function returns the value of member no_rendering_mode + * @return Value of member no_rendering_mode + */ +bool carla_msgs::msg::CarlaEpisodeSettings::no_rendering_mode() const +{ + return m_no_rendering_mode; +} + +/*! + * @brief This function returns a reference to member no_rendering_mode + * @return Reference to member no_rendering_mode + */ +bool& carla_msgs::msg::CarlaEpisodeSettings::no_rendering_mode() +{ + return m_no_rendering_mode; +} + +/*! + * @brief This function sets a value in member fixed_delta_seconds + * @param _fixed_delta_seconds New value for member fixed_delta_seconds + */ +void carla_msgs::msg::CarlaEpisodeSettings::fixed_delta_seconds( + double _fixed_delta_seconds) +{ + m_fixed_delta_seconds = _fixed_delta_seconds; +} + +/*! + * @brief This function returns the value of member fixed_delta_seconds + * @return Value of member fixed_delta_seconds + */ +double carla_msgs::msg::CarlaEpisodeSettings::fixed_delta_seconds() const +{ + return m_fixed_delta_seconds; +} + +/*! + * @brief This function returns a reference to member fixed_delta_seconds + * @return Reference to member fixed_delta_seconds + */ +double& carla_msgs::msg::CarlaEpisodeSettings::fixed_delta_seconds() +{ + return m_fixed_delta_seconds; +} + +/*! + * @brief This function sets a value in member substepping + * @param _substepping New value for member substepping + */ +void carla_msgs::msg::CarlaEpisodeSettings::substepping( + bool _substepping) +{ + m_substepping = _substepping; +} + +/*! + * @brief This function returns the value of member substepping + * @return Value of member substepping + */ +bool carla_msgs::msg::CarlaEpisodeSettings::substepping() const +{ + return m_substepping; +} + +/*! + * @brief This function returns a reference to member substepping + * @return Reference to member substepping + */ +bool& carla_msgs::msg::CarlaEpisodeSettings::substepping() +{ + return m_substepping; +} + +/*! + * @brief This function sets a value in member max_substep_delta_time + * @param _max_substep_delta_time New value for member max_substep_delta_time + */ +void carla_msgs::msg::CarlaEpisodeSettings::max_substep_delta_time( + double _max_substep_delta_time) +{ + m_max_substep_delta_time = _max_substep_delta_time; +} + +/*! + * @brief This function returns the value of member max_substep_delta_time + * @return Value of member max_substep_delta_time + */ +double carla_msgs::msg::CarlaEpisodeSettings::max_substep_delta_time() const +{ + return m_max_substep_delta_time; +} + +/*! + * @brief This function returns a reference to member max_substep_delta_time + * @return Reference to member max_substep_delta_time + */ +double& carla_msgs::msg::CarlaEpisodeSettings::max_substep_delta_time() +{ + return m_max_substep_delta_time; +} + +/*! + * @brief This function sets a value in member max_substeps + * @param _max_substeps New value for member max_substeps + */ +void carla_msgs::msg::CarlaEpisodeSettings::max_substeps( + int32_t _max_substeps) +{ + m_max_substeps = _max_substeps; +} + +/*! + * @brief This function returns the value of member max_substeps + * @return Value of member max_substeps + */ +int32_t carla_msgs::msg::CarlaEpisodeSettings::max_substeps() const +{ + return m_max_substeps; +} + +/*! + * @brief This function returns a reference to member max_substeps + * @return Reference to member max_substeps + */ +int32_t& carla_msgs::msg::CarlaEpisodeSettings::max_substeps() +{ + return m_max_substeps; +} + +/*! + * @brief This function sets a value in member max_culling_distance + * @param _max_culling_distance New value for member max_culling_distance + */ +void carla_msgs::msg::CarlaEpisodeSettings::max_culling_distance( + float _max_culling_distance) +{ + m_max_culling_distance = _max_culling_distance; +} + +/*! + * @brief This function returns the value of member max_culling_distance + * @return Value of member max_culling_distance + */ +float carla_msgs::msg::CarlaEpisodeSettings::max_culling_distance() const +{ + return m_max_culling_distance; +} + +/*! + * @brief This function returns a reference to member max_culling_distance + * @return Reference to member max_culling_distance + */ +float& carla_msgs::msg::CarlaEpisodeSettings::max_culling_distance() +{ + return m_max_culling_distance; +} + +/*! + * @brief This function sets a value in member deterministic_ragdolls + * @param _deterministic_ragdolls New value for member deterministic_ragdolls + */ +void carla_msgs::msg::CarlaEpisodeSettings::deterministic_ragdolls( + bool _deterministic_ragdolls) +{ + m_deterministic_ragdolls = _deterministic_ragdolls; +} + +/*! + * @brief This function returns the value of member deterministic_ragdolls + * @return Value of member deterministic_ragdolls + */ +bool carla_msgs::msg::CarlaEpisodeSettings::deterministic_ragdolls() const +{ + return m_deterministic_ragdolls; +} + +/*! + * @brief This function returns a reference to member deterministic_ragdolls + * @return Reference to member deterministic_ragdolls + */ +bool& carla_msgs::msg::CarlaEpisodeSettings::deterministic_ragdolls() +{ + return m_deterministic_ragdolls; +} + +/*! + * @brief This function sets a value in member tile_stream_distance + * @param _tile_stream_distance New value for member tile_stream_distance + */ +void carla_msgs::msg::CarlaEpisodeSettings::tile_stream_distance( + float _tile_stream_distance) +{ + m_tile_stream_distance = _tile_stream_distance; +} + +/*! + * @brief This function returns the value of member tile_stream_distance + * @return Value of member tile_stream_distance + */ +float carla_msgs::msg::CarlaEpisodeSettings::tile_stream_distance() const +{ + return m_tile_stream_distance; +} + +/*! + * @brief This function returns a reference to member tile_stream_distance + * @return Reference to member tile_stream_distance + */ +float& carla_msgs::msg::CarlaEpisodeSettings::tile_stream_distance() +{ + return m_tile_stream_distance; +} + +/*! + * @brief This function sets a value in member actor_active_distance + * @param _actor_active_distance New value for member actor_active_distance + */ +void carla_msgs::msg::CarlaEpisodeSettings::actor_active_distance( + float _actor_active_distance) +{ + m_actor_active_distance = _actor_active_distance; +} + +/*! + * @brief This function returns the value of member actor_active_distance + * @return Value of member actor_active_distance + */ +float carla_msgs::msg::CarlaEpisodeSettings::actor_active_distance() const +{ + return m_actor_active_distance; +} + +/*! + * @brief This function returns a reference to member actor_active_distance + * @return Reference to member actor_active_distance + */ +float& carla_msgs::msg::CarlaEpisodeSettings::actor_active_distance() +{ + return m_actor_active_distance; +} + +/*! + * @brief This function sets a value in member spectator_as_ego + * @param _spectator_as_ego New value for member spectator_as_ego + */ +void carla_msgs::msg::CarlaEpisodeSettings::spectator_as_ego( + bool _spectator_as_ego) +{ + m_spectator_as_ego = _spectator_as_ego; +} + +/*! + * @brief This function returns the value of member spectator_as_ego + * @return Value of member spectator_as_ego + */ +bool carla_msgs::msg::CarlaEpisodeSettings::spectator_as_ego() const +{ + return m_spectator_as_ego; +} + +/*! + * @brief This function returns a reference to member spectator_as_ego + * @return Reference to member spectator_as_ego + */ +bool& carla_msgs::msg::CarlaEpisodeSettings::spectator_as_ego() +{ + return m_spectator_as_ego; +} + + +size_t carla_msgs::msg::CarlaEpisodeSettings::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaEpisodeSettings::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaEpisodeSettings::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettings.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettings.h new file mode 100644 index 00000000000..5721de80b70 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettings.h @@ -0,0 +1,410 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaEpisodeSettings.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEPISODESETTINGS_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEPISODESETTINGS_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CarlaEpisodeSettings_SOURCE) +#define CarlaEpisodeSettings_DllAPI __declspec( dllexport ) +#else +#define CarlaEpisodeSettings_DllAPI __declspec( dllimport ) +#endif // CarlaEpisodeSettings_SOURCE +#else +#define CarlaEpisodeSettings_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CarlaEpisodeSettings_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace msg { + /*! + * @brief This class represents the structure CarlaEpisodeSettings defined by the user in the IDL file. + * @ingroup CARLAEPISODESETTINGS + */ + class CarlaEpisodeSettings + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaEpisodeSettings(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaEpisodeSettings(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaEpisodeSettings that will be copied. + */ + eProsima_user_DllExport CarlaEpisodeSettings( + const CarlaEpisodeSettings& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaEpisodeSettings that will be copied. + */ + eProsima_user_DllExport CarlaEpisodeSettings( + CarlaEpisodeSettings&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaEpisodeSettings that will be copied. + */ + eProsima_user_DllExport CarlaEpisodeSettings& operator =( + const CarlaEpisodeSettings& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaEpisodeSettings that will be copied. + */ + eProsima_user_DllExport CarlaEpisodeSettings& operator =( + CarlaEpisodeSettings&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaEpisodeSettings object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaEpisodeSettings& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaEpisodeSettings object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaEpisodeSettings& x) const; + + /*! + * @brief This function sets a value in member synchronous_mode + * @param _synchronous_mode New value for member synchronous_mode + */ + eProsima_user_DllExport void synchronous_mode( + bool _synchronous_mode); + + /*! + * @brief This function returns the value of member synchronous_mode + * @return Value of member synchronous_mode + */ + eProsima_user_DllExport bool synchronous_mode() const; + + /*! + * @brief This function returns a reference to member synchronous_mode + * @return Reference to member synchronous_mode + */ + eProsima_user_DllExport bool& synchronous_mode(); + + /*! + * @brief This function sets a value in member no_rendering_mode + * @param _no_rendering_mode New value for member no_rendering_mode + */ + eProsima_user_DllExport void no_rendering_mode( + bool _no_rendering_mode); + + /*! + * @brief This function returns the value of member no_rendering_mode + * @return Value of member no_rendering_mode + */ + eProsima_user_DllExport bool no_rendering_mode() const; + + /*! + * @brief This function returns a reference to member no_rendering_mode + * @return Reference to member no_rendering_mode + */ + eProsima_user_DllExport bool& no_rendering_mode(); + + /*! + * @brief This function sets a value in member fixed_delta_seconds + * @param _fixed_delta_seconds New value for member fixed_delta_seconds + */ + eProsima_user_DllExport void fixed_delta_seconds( + double _fixed_delta_seconds); + + /*! + * @brief This function returns the value of member fixed_delta_seconds + * @return Value of member fixed_delta_seconds + */ + eProsima_user_DllExport double fixed_delta_seconds() const; + + /*! + * @brief This function returns a reference to member fixed_delta_seconds + * @return Reference to member fixed_delta_seconds + */ + eProsima_user_DllExport double& fixed_delta_seconds(); + + /*! + * @brief This function sets a value in member substepping + * @param _substepping New value for member substepping + */ + eProsima_user_DllExport void substepping( + bool _substepping); + + /*! + * @brief This function returns the value of member substepping + * @return Value of member substepping + */ + eProsima_user_DllExport bool substepping() const; + + /*! + * @brief This function returns a reference to member substepping + * @return Reference to member substepping + */ + eProsima_user_DllExport bool& substepping(); + + /*! + * @brief This function sets a value in member max_substep_delta_time + * @param _max_substep_delta_time New value for member max_substep_delta_time + */ + eProsima_user_DllExport void max_substep_delta_time( + double _max_substep_delta_time); + + /*! + * @brief This function returns the value of member max_substep_delta_time + * @return Value of member max_substep_delta_time + */ + eProsima_user_DllExport double max_substep_delta_time() const; + + /*! + * @brief This function returns a reference to member max_substep_delta_time + * @return Reference to member max_substep_delta_time + */ + eProsima_user_DllExport double& max_substep_delta_time(); + + /*! + * @brief This function sets a value in member max_substeps + * @param _max_substeps New value for member max_substeps + */ + eProsima_user_DllExport void max_substeps( + int32_t _max_substeps); + + /*! + * @brief This function returns the value of member max_substeps + * @return Value of member max_substeps + */ + eProsima_user_DllExport int32_t max_substeps() const; + + /*! + * @brief This function returns a reference to member max_substeps + * @return Reference to member max_substeps + */ + eProsima_user_DllExport int32_t& max_substeps(); + + /*! + * @brief This function sets a value in member max_culling_distance + * @param _max_culling_distance New value for member max_culling_distance + */ + eProsima_user_DllExport void max_culling_distance( + float _max_culling_distance); + + /*! + * @brief This function returns the value of member max_culling_distance + * @return Value of member max_culling_distance + */ + eProsima_user_DllExport float max_culling_distance() const; + + /*! + * @brief This function returns a reference to member max_culling_distance + * @return Reference to member max_culling_distance + */ + eProsima_user_DllExport float& max_culling_distance(); + + /*! + * @brief This function sets a value in member deterministic_ragdolls + * @param _deterministic_ragdolls New value for member deterministic_ragdolls + */ + eProsima_user_DllExport void deterministic_ragdolls( + bool _deterministic_ragdolls); + + /*! + * @brief This function returns the value of member deterministic_ragdolls + * @return Value of member deterministic_ragdolls + */ + eProsima_user_DllExport bool deterministic_ragdolls() const; + + /*! + * @brief This function returns a reference to member deterministic_ragdolls + * @return Reference to member deterministic_ragdolls + */ + eProsima_user_DllExport bool& deterministic_ragdolls(); + + /*! + * @brief This function sets a value in member tile_stream_distance + * @param _tile_stream_distance New value for member tile_stream_distance + */ + eProsima_user_DllExport void tile_stream_distance( + float _tile_stream_distance); + + /*! + * @brief This function returns the value of member tile_stream_distance + * @return Value of member tile_stream_distance + */ + eProsima_user_DllExport float tile_stream_distance() const; + + /*! + * @brief This function returns a reference to member tile_stream_distance + * @return Reference to member tile_stream_distance + */ + eProsima_user_DllExport float& tile_stream_distance(); + + /*! + * @brief This function sets a value in member actor_active_distance + * @param _actor_active_distance New value for member actor_active_distance + */ + eProsima_user_DllExport void actor_active_distance( + float _actor_active_distance); + + /*! + * @brief This function returns the value of member actor_active_distance + * @return Value of member actor_active_distance + */ + eProsima_user_DllExport float actor_active_distance() const; + + /*! + * @brief This function returns a reference to member actor_active_distance + * @return Reference to member actor_active_distance + */ + eProsima_user_DllExport float& actor_active_distance(); + + /*! + * @brief This function sets a value in member spectator_as_ego + * @param _spectator_as_ego New value for member spectator_as_ego + */ + eProsima_user_DllExport void spectator_as_ego( + bool _spectator_as_ego); + + /*! + * @brief This function returns the value of member spectator_as_ego + * @return Value of member spectator_as_ego + */ + eProsima_user_DllExport bool spectator_as_ego() const; + + /*! + * @brief This function returns a reference to member spectator_as_ego + * @return Reference to member spectator_as_ego + */ + eProsima_user_DllExport bool& spectator_as_ego(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::msg::CarlaEpisodeSettings& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + bool m_synchronous_mode; + bool m_no_rendering_mode; + double m_fixed_delta_seconds; + bool m_substepping; + double m_max_substep_delta_time; + int32_t m_max_substeps; + float m_max_culling_distance; + bool m_deterministic_ragdolls; + float m_tile_stream_distance; + float m_actor_active_distance; + bool m_spectator_as_ego; + }; + } // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEPISODESETTINGS_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettingsPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettingsPubSubTypes.cxx new file mode 100644 index 00000000000..6ce6b26d917 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettingsPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaEpisodeSettingsPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaEpisodeSettingsPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaEpisodeSettingsPubSubType::CarlaEpisodeSettingsPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaEpisodeSettings_"); + auto type_size = CarlaEpisodeSettings::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaEpisodeSettings::isKeyDefined(); + size_t keyLength = CarlaEpisodeSettings::getKeyMaxCdrSerializedSize() > 16 ? + CarlaEpisodeSettings::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaEpisodeSettingsPubSubType::~CarlaEpisodeSettingsPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaEpisodeSettingsPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaEpisodeSettings* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaEpisodeSettingsPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaEpisodeSettings* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaEpisodeSettingsPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaEpisodeSettingsPubSubType::createData() + { + return reinterpret_cast(new CarlaEpisodeSettings()); + } + + void CarlaEpisodeSettingsPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaEpisodeSettingsPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaEpisodeSettings* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaEpisodeSettings::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaEpisodeSettings::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettingsPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettingsPubSubTypes.h new file mode 100644 index 00000000000..48925fde9b8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettingsPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaEpisodeSettingsPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEPISODESETTINGS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEPISODESETTINGS_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaEpisodeSettings.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaEpisodeSettings is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CarlaEpisodeSettings defined by the user in the IDL file. + * @ingroup CARLAEPISODESETTINGS + */ + class CarlaEpisodeSettingsPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaEpisodeSettings type; + + eProsima_user_DllExport CarlaEpisodeSettingsPubSubType(); + + eProsima_user_DllExport virtual ~CarlaEpisodeSettingsPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) CarlaEpisodeSettings(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEPISODESETTINGS_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/CarlaLineInvasion.cpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasion.cxx similarity index 99% rename from LibCarla/source/carla/ros2/types/CarlaLineInvasion.cpp rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasion.cxx index ce483598762..64292e68d9a 100644 --- a/LibCarla/source/carla/ros2/types/CarlaLineInvasion.cpp +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasion.cxx @@ -13,7 +13,7 @@ // limitations under the License. /*! - * @file CarlaLineInvasion.cpp + * @file CarlaLaneInvasion.cpp * This source file contains the definition of the described types in the IDL file. * * This file was generated by the tool gen. @@ -26,7 +26,7 @@ char dummy; } // namespace #endif // _WIN32 -#include "CarlaLineInvasion.h" +#include "CarlaLaneInvasion.h" #include #include diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasion.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasion.h new file mode 100644 index 00000000000..236cf4fc08e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasion.h @@ -0,0 +1,225 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaLaneInvasion.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CarlaLaneInvasion_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CarlaLaneInvasion_H_ + +#include "std_msgs/msg/Header.h" + +#include + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CarlaLaneInvasion_SOURCE) +#define CarlaLaneInvasion_DllAPI __declspec(dllexport) +#else +#define CarlaLaneInvasion_DllAPI __declspec(dllimport) +#endif // CarlaLaneInvasion_SOURCE +#else +#define CarlaLaneInvasion_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CarlaLaneInvasion_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace carla_msgs { +namespace msg { +const int32_t LANE_MARKING_OTHER = 0; +const int32_t LANE_MARKING_BROKEN = 1; +const int32_t LANE_MARKING_SOLID = 2; +/*! + * @brief This class represents the structure LaneInvasionEvent defined by the user in the IDL file. + * @ingroup CarlaLaneInvasion + */ +class LaneInvasionEvent { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport LaneInvasionEvent(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~LaneInvasionEvent(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::LaneInvasionEvent that will be copied. + */ + eProsima_user_DllExport LaneInvasionEvent(const LaneInvasionEvent& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::LaneInvasionEvent that will be copied. + */ + eProsima_user_DllExport LaneInvasionEvent(LaneInvasionEvent&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::LaneInvasionEvent that will be copied. + */ + eProsima_user_DllExport LaneInvasionEvent& operator=(const LaneInvasionEvent& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::LaneInvasionEvent that will be copied. + */ + eProsima_user_DllExport LaneInvasionEvent& operator=(LaneInvasionEvent&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::LaneInvasionEvent object to compare. + */ + eProsima_user_DllExport bool operator==(const LaneInvasionEvent& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::LaneInvasionEvent object to compare. + */ + eProsima_user_DllExport bool operator!=(const LaneInvasionEvent& x) const; + + /*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ + eProsima_user_DllExport void header(const std_msgs::msg::Header& _header); + + /*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ + eProsima_user_DllExport void header(std_msgs::msg::Header&& _header); + + /*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ + eProsima_user_DllExport const std_msgs::msg::Header& header() const; + + /*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ + eProsima_user_DllExport std_msgs::msg::Header& header(); + /*! + * @brief This function copies the value in member crossed_lane_markings + * @param _crossed_lane_markings New value to be copied in member crossed_lane_markings + */ + eProsima_user_DllExport void crossed_lane_markings(const std::vector& _crossed_lane_markings); + + /*! + * @brief This function moves the value in member crossed_lane_markings + * @param _crossed_lane_markings New value to be moved in member crossed_lane_markings + */ + eProsima_user_DllExport void crossed_lane_markings(std::vector&& _crossed_lane_markings); + + /*! + * @brief This function returns a constant reference to member crossed_lane_markings + * @return Constant reference to member crossed_lane_markings + */ + eProsima_user_DllExport const std::vector& crossed_lane_markings() const; + + /*! + * @brief This function returns a reference to member crossed_lane_markings + * @return Reference to member crossed_lane_markings + */ + eProsima_user_DllExport std::vector& crossed_lane_markings(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const carla_msgs::msg::LaneInvasionEvent& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + std_msgs::msg::Header m_header; + std::vector m_crossed_lane_markings; +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CarlaLaneInvasion_H_ diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEvent.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEvent.cxx new file mode 100644 index 00000000000..a5bdfe541b8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEvent.cxx @@ -0,0 +1,255 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaLaneInvasionEvent.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaLaneInvasionEvent.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + +carla_msgs::msg::CarlaLaneInvasionEvent::CarlaLaneInvasionEvent() +{ + // m_header com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@2f217633 + + // m_crossed_lane_markings com.eprosima.idl.parser.typecode.SequenceTypeCode@5acf93bb + + +} + +carla_msgs::msg::CarlaLaneInvasionEvent::~CarlaLaneInvasionEvent() +{ + +} + +carla_msgs::msg::CarlaLaneInvasionEvent::CarlaLaneInvasionEvent( + const CarlaLaneInvasionEvent& x) +{ + m_header = x.m_header; + m_crossed_lane_markings = x.m_crossed_lane_markings; +} + +carla_msgs::msg::CarlaLaneInvasionEvent::CarlaLaneInvasionEvent( + CarlaLaneInvasionEvent&& x) +{ + m_header = std::move(x.m_header); + m_crossed_lane_markings = std::move(x.m_crossed_lane_markings); +} + +carla_msgs::msg::CarlaLaneInvasionEvent& carla_msgs::msg::CarlaLaneInvasionEvent::operator =( + const CarlaLaneInvasionEvent& x) +{ + + m_header = x.m_header; + m_crossed_lane_markings = x.m_crossed_lane_markings; + + return *this; +} + +carla_msgs::msg::CarlaLaneInvasionEvent& carla_msgs::msg::CarlaLaneInvasionEvent::operator =( + CarlaLaneInvasionEvent&& x) +{ + + m_header = std::move(x.m_header); + m_crossed_lane_markings = std::move(x.m_crossed_lane_markings); + + return *this; +} + +bool carla_msgs::msg::CarlaLaneInvasionEvent::operator ==( + const CarlaLaneInvasionEvent& x) const +{ + + return (m_header == x.m_header && m_crossed_lane_markings == x.m_crossed_lane_markings); +} + +bool carla_msgs::msg::CarlaLaneInvasionEvent::operator !=( + const CarlaLaneInvasionEvent& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaLaneInvasionEvent::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getMaxCdrSerializedSize(current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + current_alignment += (100 * 4) + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaLaneInvasionEvent::getCdrSerializedSize( + const carla_msgs::msg::CarlaLaneInvasionEvent& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getCdrSerializedSize(data.header(), current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + if (data.crossed_lane_markings().size() > 0) + { + current_alignment += (data.crossed_lane_markings().size() * 4) + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + } + + + + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaLaneInvasionEvent::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_header; + scdr << m_crossed_lane_markings; + +} + +void carla_msgs::msg::CarlaLaneInvasionEvent::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_header; + dcdr >> m_crossed_lane_markings; +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void carla_msgs::msg::CarlaLaneInvasionEvent::header( + const std_msgs::msg::Header& _header) +{ + m_header = _header; +} + +/*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ +void carla_msgs::msg::CarlaLaneInvasionEvent::header( + std_msgs::msg::Header&& _header) +{ + m_header = std::move(_header); +} + +/*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ +const std_msgs::msg::Header& carla_msgs::msg::CarlaLaneInvasionEvent::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& carla_msgs::msg::CarlaLaneInvasionEvent::header() +{ + return m_header; +} +/*! + * @brief This function copies the value in member crossed_lane_markings + * @param _crossed_lane_markings New value to be copied in member crossed_lane_markings + */ +void carla_msgs::msg::CarlaLaneInvasionEvent::crossed_lane_markings( + const std::vector& _crossed_lane_markings) +{ + m_crossed_lane_markings = _crossed_lane_markings; +} + +/*! + * @brief This function moves the value in member crossed_lane_markings + * @param _crossed_lane_markings New value to be moved in member crossed_lane_markings + */ +void carla_msgs::msg::CarlaLaneInvasionEvent::crossed_lane_markings( + std::vector&& _crossed_lane_markings) +{ + m_crossed_lane_markings = std::move(_crossed_lane_markings); +} + +/*! + * @brief This function returns a constant reference to member crossed_lane_markings + * @return Constant reference to member crossed_lane_markings + */ +const std::vector& carla_msgs::msg::CarlaLaneInvasionEvent::crossed_lane_markings() const +{ + return m_crossed_lane_markings; +} + +/*! + * @brief This function returns a reference to member crossed_lane_markings + * @return Reference to member crossed_lane_markings + */ +std::vector& carla_msgs::msg::CarlaLaneInvasionEvent::crossed_lane_markings() +{ + return m_crossed_lane_markings; +} + +size_t carla_msgs::msg::CarlaLaneInvasionEvent::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaLaneInvasionEvent::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaLaneInvasionEvent::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/types/CarlaLineInvasion.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEvent.h similarity index 74% rename from LibCarla/source/carla/ros2/types/CarlaLineInvasion.h rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEvent.h index b1077107c40..c91607f1d4e 100644 --- a/LibCarla/source/carla/ros2/types/CarlaLineInvasion.h +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEvent.h @@ -13,18 +13,16 @@ // limitations under the License. /*! - * @file CarlaLineInvasion.h + * @file CarlaLaneInvasionEvent.h * This header file contains the declaration of the described types in the IDL file. * * This file was generated by the tool gen. */ -#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALINEINVASION_H_ -#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALINEINVASION_H_ +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALANEINVASIONEVENT_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALANEINVASIONEVENT_H_ -#include "Header.h" - -#include +#include "std_msgs/msg/Header.h" #include #include @@ -45,16 +43,16 @@ #if defined(_WIN32) #if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(CarlaLineInvasion_SOURCE) -#define CarlaLineInvasion_DllAPI __declspec( dllexport ) +#if defined(CarlaLaneInvasionEvent_SOURCE) +#define CarlaLaneInvasionEvent_DllAPI __declspec( dllexport ) #else -#define CarlaLineInvasion_DllAPI __declspec( dllimport ) -#endif // CarlaLineInvasion_SOURCE +#define CarlaLaneInvasionEvent_DllAPI __declspec( dllimport ) +#endif // CarlaLaneInvasionEvent_SOURCE #else -#define CarlaLineInvasion_DllAPI +#define CarlaLaneInvasionEvent_DllAPI #endif // EPROSIMA_USER_DLL_EXPORT #else -#define CarlaLineInvasion_DllAPI +#define CarlaLaneInvasionEvent_DllAPI #endif // _WIN32 namespace eprosima { @@ -63,69 +61,73 @@ class Cdr; } // namespace fastcdr } // namespace eprosima + namespace carla_msgs { namespace msg { - const int32_t LANE_MARKING_OTHER = 0; - const int32_t LANE_MARKING_BROKEN = 1; - const int32_t LANE_MARKING_SOLID = 2; + namespace CarlaLaneInvasionEvent_Constants { + const int32_t LANE_MARKING_OTHER = 0; + const int32_t LANE_MARKING_BROKEN = 1; + const int32_t LANE_MARKING_SOLID = 2; + } // namespace CarlaLaneInvasionEvent_Constants /*! - * @brief This class represents the structure LaneInvasionEvent defined by the user in the IDL file. - * @ingroup CARLALINEINVASION + * @brief This class represents the structure CarlaLaneInvasionEvent defined by the user in the IDL file. + * @ingroup CARLALANEINVASIONEVENT */ - class LaneInvasionEvent + class CarlaLaneInvasionEvent { public: + /*! * @brief Default constructor. */ - eProsima_user_DllExport LaneInvasionEvent(); + eProsima_user_DllExport CarlaLaneInvasionEvent(); /*! * @brief Default destructor. */ - eProsima_user_DllExport ~LaneInvasionEvent(); + eProsima_user_DllExport ~CarlaLaneInvasionEvent(); /*! * @brief Copy constructor. - * @param x Reference to the object carla_msgs::msg::LaneInvasionEvent that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaLaneInvasionEvent that will be copied. */ - eProsima_user_DllExport LaneInvasionEvent( - const LaneInvasionEvent& x); + eProsima_user_DllExport CarlaLaneInvasionEvent( + const CarlaLaneInvasionEvent& x); /*! * @brief Move constructor. - * @param x Reference to the object carla_msgs::msg::LaneInvasionEvent that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaLaneInvasionEvent that will be copied. */ - eProsima_user_DllExport LaneInvasionEvent( - LaneInvasionEvent&& x) noexcept; + eProsima_user_DllExport CarlaLaneInvasionEvent( + CarlaLaneInvasionEvent&& x); /*! * @brief Copy assignment. - * @param x Reference to the object carla_msgs::msg::LaneInvasionEvent that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaLaneInvasionEvent that will be copied. */ - eProsima_user_DllExport LaneInvasionEvent& operator =( - const LaneInvasionEvent& x); + eProsima_user_DllExport CarlaLaneInvasionEvent& operator =( + const CarlaLaneInvasionEvent& x); /*! * @brief Move assignment. - * @param x Reference to the object carla_msgs::msg::LaneInvasionEvent that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaLaneInvasionEvent that will be copied. */ - eProsima_user_DllExport LaneInvasionEvent& operator =( - LaneInvasionEvent&& x) noexcept; + eProsima_user_DllExport CarlaLaneInvasionEvent& operator =( + CarlaLaneInvasionEvent&& x); /*! * @brief Comparison operator. - * @param x carla_msgs::msg::LaneInvasionEvent object to compare. + * @param x carla_msgs::msg::CarlaLaneInvasionEvent object to compare. */ eProsima_user_DllExport bool operator ==( - const LaneInvasionEvent& x) const; + const CarlaLaneInvasionEvent& x) const; /*! * @brief Comparison operator. - * @param x carla_msgs::msg::LaneInvasionEvent object to compare. + * @param x carla_msgs::msg::CarlaLaneInvasionEvent object to compare. */ eProsima_user_DllExport bool operator !=( - const LaneInvasionEvent& x) const; + const CarlaLaneInvasionEvent& x) const; /*! * @brief This function copies the value in member header @@ -179,11 +181,11 @@ namespace carla_msgs { eProsima_user_DllExport std::vector& crossed_lane_markings(); /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -194,9 +196,10 @@ namespace carla_msgs { * @return Serialized size. */ eProsima_user_DllExport static size_t getCdrSerializedSize( - const carla_msgs::msg::LaneInvasionEvent& data, + const carla_msgs::msg::CarlaLaneInvasionEvent& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -211,6 +214,8 @@ namespace carla_msgs { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -233,10 +238,11 @@ namespace carla_msgs { eprosima::fastcdr::Cdr& cdr) const; private: + std_msgs::msg::Header m_header; std::vector m_crossed_lane_markings; }; } // namespace msg } // namespace carla_msgs -#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALINEINVASION_H_ +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALANEINVASIONEVENT_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEventPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEventPubSubTypes.cxx new file mode 100644 index 00000000000..0c2df428c3c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEventPubSubTypes.cxx @@ -0,0 +1,182 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaLaneInvasionEventPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaLaneInvasionEventPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + namespace CarlaLaneInvasionEvent_Constants { + + + + + } //End of namespace CarlaLaneInvasionEvent_Constants + CarlaLaneInvasionEventPubSubType::CarlaLaneInvasionEventPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaLaneInvasionEvent_"); + auto type_size = CarlaLaneInvasionEvent::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaLaneInvasionEvent::isKeyDefined(); + size_t keyLength = CarlaLaneInvasionEvent::getKeyMaxCdrSerializedSize() > 16 ? + CarlaLaneInvasionEvent::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaLaneInvasionEventPubSubType::~CarlaLaneInvasionEventPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaLaneInvasionEventPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaLaneInvasionEvent* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaLaneInvasionEventPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaLaneInvasionEvent* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaLaneInvasionEventPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaLaneInvasionEventPubSubType::createData() + { + return reinterpret_cast(new CarlaLaneInvasionEvent()); + } + + void CarlaLaneInvasionEventPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaLaneInvasionEventPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaLaneInvasionEvent* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaLaneInvasionEvent::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaLaneInvasionEvent::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/types/CarlaEgoVehicleControlPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEventPubSubTypes.h similarity index 76% rename from LibCarla/source/carla/ros2/types/CarlaEgoVehicleControlPubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEventPubSubTypes.h index 4d064e66a79..6e6bb375272 100644 --- a/LibCarla/source/carla/ros2/types/CarlaEgoVehicleControlPubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEventPubSubTypes.h @@ -13,44 +13,49 @@ // limitations under the License. /*! - * @file CarlaEgoCarlaEgoVehicleControlPubSubTypes.h + * @file CarlaLaneInvasionEventPubSubTypes.h * This header file contains the declaration of the serialization functions. * * This file was generated by the tool fastcdrgen. */ -#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOCarlaEgoVehicleControl_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOCarlaEgoVehicleControl_PUBSUBTYPES_H_ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALANEINVASIONEVENT_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALANEINVASIONEVENT_PUBSUBTYPES_H_ #include #include -#include "CarlaEgoVehicleControl.h" - -#include "HeaderPubSubTypes.h" +#include "CarlaLaneInvasionEvent.h" #if !defined(GEN_API_VER) || (GEN_API_VER != 1) #error \ - Generated CarlaEgoCarlaEgoVehicleControl is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. + Generated CarlaLaneInvasionEvent is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. #endif // GEN_API_VER namespace carla_msgs { namespace msg { + namespace CarlaLaneInvasionEvent_Constants + { + + + + } /*! - * @brief This class represents the TopicDataType of the type CarlaEgoVehicleControl defined by the user in the IDL file. - * @ingroup CarlaEgoVehicleControl + * @brief This class represents the TopicDataType of the type CarlaLaneInvasionEvent defined by the user in the IDL file. + * @ingroup CARLALANEINVASIONEVENT */ - class CarlaEgoVehicleControlPubSubType : public eprosima::fastdds::dds::TopicDataType + class CarlaLaneInvasionEventPubSubType : public eprosima::fastdds::dds::TopicDataType { public: - typedef CarlaEgoVehicleControl type; + typedef CarlaLaneInvasionEvent type; - eProsima_user_DllExport CarlaEgoVehicleControlPubSubType(); + eProsima_user_DllExport CarlaLaneInvasionEventPubSubType(); - eProsima_user_DllExport virtual ~CarlaEgoVehicleControlPubSubType() override; + eProsima_user_DllExport virtual ~CarlaLaneInvasionEventPubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -98,10 +103,11 @@ namespace carla_msgs } #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; unsigned char* m_keyBuffer; }; } } -#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOCarlaEgoVehicleControl_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALANEINVASIONEVENT_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/CarlaLineInvasionPubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionPubSubTypes.cxx similarity index 98% rename from LibCarla/source/carla/ros2/types/CarlaLineInvasionPubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionPubSubTypes.cxx index d23c113c4b2..65535475f00 100644 --- a/LibCarla/source/carla/ros2/types/CarlaLineInvasionPubSubTypes.cpp +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionPubSubTypes.cxx @@ -13,7 +13,7 @@ // limitations under the License. /*! - * @file CarlaLineInvasionPubSubTypes.cpp + * @file CarlaLaneInvasionPubSubTypes.cpp * This header file contains the implementation of the serialization functions. * * This file was generated by the tool fastcdrgen. @@ -22,7 +22,7 @@ #include #include -#include "CarlaLineInvasionPubSubTypes.h" +#include "CarlaLaneInvasionPubSubTypes.h" using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionPubSubTypes.h new file mode 100644 index 00000000000..2c5620a95a6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionPubSubTypes.h @@ -0,0 +1,92 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaLaneInvasionPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CarlaLaneInvasion_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CarlaLaneInvasion_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaLaneInvasion.h" +#include "std_msgs/msg/HeaderPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaLaneInvasion is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs { +namespace msg { +/*! + * @brief This class represents the TopicDataType of the type LaneInvasionEvent defined by the user in the IDL file. + * @ingroup CarlaLaneInvasion + */ +class LaneInvasionEventPubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef LaneInvasionEvent type; + + eProsima_user_DllExport LaneInvasionEventPubSubType(); + + eProsima_user_DllExport virtual ~LaneInvasionEventPubSubType() override; + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + (void)memory; + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; + unsigned char* m_keyBuffer; +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CarlaLaneInvasion_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatus.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatus.cxx new file mode 100644 index 00000000000..605e06bd6d1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatus.cxx @@ -0,0 +1,384 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaStatus.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaStatus.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaStatus::CarlaStatus() +{ + // m_header com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@5b03b9fe + + // m_episode_settings com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@37d4349f + + // m_frame com.eprosima.idl.parser.typecode.PrimitiveTypeCode@434a63ab + m_frame = 0; + // m_synchronous_mode_participant_states com.eprosima.idl.parser.typecode.SequenceTypeCode@6e0f5f7f + + // m_game_running com.eprosima.idl.parser.typecode.PrimitiveTypeCode@2805d709 + m_game_running = false; + +} + +carla_msgs::msg::CarlaStatus::~CarlaStatus() +{ + + + + +} + +carla_msgs::msg::CarlaStatus::CarlaStatus( + const CarlaStatus& x) +{ + m_header = x.m_header; + m_episode_settings = x.m_episode_settings; + m_frame = x.m_frame; + m_synchronous_mode_participant_states = x.m_synchronous_mode_participant_states; + m_game_running = x.m_game_running; +} + +carla_msgs::msg::CarlaStatus::CarlaStatus( + CarlaStatus&& x) +{ + m_header = std::move(x.m_header); + m_episode_settings = std::move(x.m_episode_settings); + m_frame = x.m_frame; + m_synchronous_mode_participant_states = std::move(x.m_synchronous_mode_participant_states); + m_game_running = x.m_game_running; +} + +carla_msgs::msg::CarlaStatus& carla_msgs::msg::CarlaStatus::operator =( + const CarlaStatus& x) +{ + + m_header = x.m_header; + m_episode_settings = x.m_episode_settings; + m_frame = x.m_frame; + m_synchronous_mode_participant_states = x.m_synchronous_mode_participant_states; + m_game_running = x.m_game_running; + + return *this; +} + +carla_msgs::msg::CarlaStatus& carla_msgs::msg::CarlaStatus::operator =( + CarlaStatus&& x) +{ + + m_header = std::move(x.m_header); + m_episode_settings = std::move(x.m_episode_settings); + m_frame = x.m_frame; + m_synchronous_mode_participant_states = std::move(x.m_synchronous_mode_participant_states); + m_game_running = x.m_game_running; + + return *this; +} + +bool carla_msgs::msg::CarlaStatus::operator ==( + const CarlaStatus& x) const +{ + + return (m_header == x.m_header && m_episode_settings == x.m_episode_settings && m_frame == x.m_frame && m_synchronous_mode_participant_states == x.m_synchronous_mode_participant_states && m_game_running == x.m_game_running); +} + +bool carla_msgs::msg::CarlaStatus::operator !=( + const CarlaStatus& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaStatus::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getMaxCdrSerializedSize(current_alignment); + current_alignment += carla_msgs::msg::CarlaEpisodeSettings::getMaxCdrSerializedSize(current_alignment); + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < 100; ++a) + { + current_alignment += carla_msgs::msg::CarlaSynchronizationWindowParticipantState::getMaxCdrSerializedSize(current_alignment);} + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaStatus::getCdrSerializedSize( + const carla_msgs::msg::CarlaStatus& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getCdrSerializedSize(data.header(), current_alignment); + current_alignment += carla_msgs::msg::CarlaEpisodeSettings::getCdrSerializedSize(data.episode_settings(), current_alignment); + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < data.synchronous_mode_participant_states().size(); ++a) + { + current_alignment += carla_msgs::msg::CarlaSynchronizationWindowParticipantState::getCdrSerializedSize(data.synchronous_mode_participant_states().at(a), current_alignment);} + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaStatus::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_header; + scdr << m_episode_settings; + scdr << m_frame; + scdr << m_synchronous_mode_participant_states; + scdr << m_game_running; + +} + +void carla_msgs::msg::CarlaStatus::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_header; + dcdr >> m_episode_settings; + dcdr >> m_frame; + dcdr >> m_synchronous_mode_participant_states; + dcdr >> m_game_running; +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void carla_msgs::msg::CarlaStatus::header( + const std_msgs::msg::Header& _header) +{ + m_header = _header; +} + +/*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ +void carla_msgs::msg::CarlaStatus::header( + std_msgs::msg::Header&& _header) +{ + m_header = std::move(_header); +} + +/*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ +const std_msgs::msg::Header& carla_msgs::msg::CarlaStatus::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& carla_msgs::msg::CarlaStatus::header() +{ + return m_header; +} +/*! + * @brief This function copies the value in member episode_settings + * @param _episode_settings New value to be copied in member episode_settings + */ +void carla_msgs::msg::CarlaStatus::episode_settings( + const carla_msgs::msg::CarlaEpisodeSettings& _episode_settings) +{ + m_episode_settings = _episode_settings; +} + +/*! + * @brief This function moves the value in member episode_settings + * @param _episode_settings New value to be moved in member episode_settings + */ +void carla_msgs::msg::CarlaStatus::episode_settings( + carla_msgs::msg::CarlaEpisodeSettings&& _episode_settings) +{ + m_episode_settings = std::move(_episode_settings); +} + +/*! + * @brief This function returns a constant reference to member episode_settings + * @return Constant reference to member episode_settings + */ +const carla_msgs::msg::CarlaEpisodeSettings& carla_msgs::msg::CarlaStatus::episode_settings() const +{ + return m_episode_settings; +} + +/*! + * @brief This function returns a reference to member episode_settings + * @return Reference to member episode_settings + */ +carla_msgs::msg::CarlaEpisodeSettings& carla_msgs::msg::CarlaStatus::episode_settings() +{ + return m_episode_settings; +} +/*! + * @brief This function sets a value in member frame + * @param _frame New value for member frame + */ +void carla_msgs::msg::CarlaStatus::frame( + uint64_t _frame) +{ + m_frame = _frame; +} + +/*! + * @brief This function returns the value of member frame + * @return Value of member frame + */ +uint64_t carla_msgs::msg::CarlaStatus::frame() const +{ + return m_frame; +} + +/*! + * @brief This function returns a reference to member frame + * @return Reference to member frame + */ +uint64_t& carla_msgs::msg::CarlaStatus::frame() +{ + return m_frame; +} + +/*! + * @brief This function copies the value in member synchronous_mode_participant_states + * @param _synchronous_mode_participant_states New value to be copied in member synchronous_mode_participant_states + */ +void carla_msgs::msg::CarlaStatus::synchronous_mode_participant_states( + const std::vector& _synchronous_mode_participant_states) +{ + m_synchronous_mode_participant_states = _synchronous_mode_participant_states; +} + +/*! + * @brief This function moves the value in member synchronous_mode_participant_states + * @param _synchronous_mode_participant_states New value to be moved in member synchronous_mode_participant_states + */ +void carla_msgs::msg::CarlaStatus::synchronous_mode_participant_states( + std::vector&& _synchronous_mode_participant_states) +{ + m_synchronous_mode_participant_states = std::move(_synchronous_mode_participant_states); +} + +/*! + * @brief This function returns a constant reference to member synchronous_mode_participant_states + * @return Constant reference to member synchronous_mode_participant_states + */ +const std::vector& carla_msgs::msg::CarlaStatus::synchronous_mode_participant_states() const +{ + return m_synchronous_mode_participant_states; +} + +/*! + * @brief This function returns a reference to member synchronous_mode_participant_states + * @return Reference to member synchronous_mode_participant_states + */ +std::vector& carla_msgs::msg::CarlaStatus::synchronous_mode_participant_states() +{ + return m_synchronous_mode_participant_states; +} +/*! + * @brief This function sets a value in member game_running + * @param _game_running New value for member game_running + */ +void carla_msgs::msg::CarlaStatus::game_running( + bool _game_running) +{ + m_game_running = _game_running; +} + +/*! + * @brief This function returns the value of member game_running + * @return Value of member game_running + */ +bool carla_msgs::msg::CarlaStatus::game_running() const +{ + return m_game_running; +} + +/*! + * @brief This function returns a reference to member game_running + * @return Reference to member game_running + */ +bool& carla_msgs::msg::CarlaStatus::game_running() +{ + return m_game_running; +} + + +size_t carla_msgs::msg::CarlaStatus::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaStatus::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaStatus::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/types/Image.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatus.h similarity index 52% rename from LibCarla/source/carla/ros2/types/Image.h rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatus.h index 3f8114c04d7..18f6fec771b 100644 --- a/LibCarla/source/carla/ros2/types/Image.h +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatus.h @@ -13,18 +13,18 @@ // limitations under the License. /*! - * @file Image.h + * @file CarlaStatus.h * This header file contains the declaration of the described types in the IDL file. * * This file was generated by the tool gen. */ -#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGE_H_ -#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGE_H_ +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASTATUS_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASTATUS_H_ -#include "Header.h" - -#include +#include "CarlaSynchronizationWindowParticipantState.h" +#include "std_msgs/msg/Header.h" +#include "CarlaEpisodeSettings.h" #include #include @@ -45,16 +45,16 @@ #if defined(_WIN32) #if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(Image_SOURCE) -#define Image_DllAPI __declspec( dllexport ) +#if defined(CarlaStatus_SOURCE) +#define CarlaStatus_DllAPI __declspec( dllexport ) #else -#define Image_DllAPI __declspec( dllimport ) -#endif // Image_SOURCE +#define CarlaStatus_DllAPI __declspec( dllimport ) +#endif // CarlaStatus_SOURCE #else -#define Image_DllAPI +#define CarlaStatus_DllAPI #endif // EPROSIMA_USER_DLL_EXPORT #else -#define Image_DllAPI +#define CarlaStatus_DllAPI #endif // _WIN32 namespace eprosima { @@ -63,67 +63,68 @@ class Cdr; } // namespace fastcdr } // namespace eprosima -namespace sensor_msgs { + +namespace carla_msgs { namespace msg { /*! - * @brief This class represents the structure Image defined by the user in the IDL file. - * @ingroup IMAGE + * @brief This class represents the structure CarlaStatus defined by the user in the IDL file. + * @ingroup CARLASTATUS */ - class Image + class CarlaStatus { public: /*! * @brief Default constructor. */ - eProsima_user_DllExport Image(); + eProsima_user_DllExport CarlaStatus(); /*! * @brief Default destructor. */ - eProsima_user_DllExport ~Image(); + eProsima_user_DllExport ~CarlaStatus(); /*! * @brief Copy constructor. - * @param x Reference to the object sensor_msgs::msg::Image that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaStatus that will be copied. */ - eProsima_user_DllExport Image( - const Image& x); + eProsima_user_DllExport CarlaStatus( + const CarlaStatus& x); /*! * @brief Move constructor. - * @param x Reference to the object sensor_msgs::msg::Image that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaStatus that will be copied. */ - eProsima_user_DllExport Image( - Image&& x) noexcept; + eProsima_user_DllExport CarlaStatus( + CarlaStatus&& x); /*! * @brief Copy assignment. - * @param x Reference to the object sensor_msgs::msg::Image that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaStatus that will be copied. */ - eProsima_user_DllExport Image& operator =( - const Image& x); + eProsima_user_DllExport CarlaStatus& operator =( + const CarlaStatus& x); /*! * @brief Move assignment. - * @param x Reference to the object sensor_msgs::msg::Image that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaStatus that will be copied. */ - eProsima_user_DllExport Image& operator =( - Image&& x) noexcept; + eProsima_user_DllExport CarlaStatus& operator =( + CarlaStatus&& x); /*! * @brief Comparison operator. - * @param x sensor_msgs::msg::Image object to compare. + * @param x carla_msgs::msg::CarlaStatus object to compare. */ eProsima_user_DllExport bool operator ==( - const Image& x) const; + const CarlaStatus& x) const; /*! * @brief Comparison operator. - * @param x sensor_msgs::msg::Image object to compare. + * @param x carla_msgs::msg::CarlaStatus object to compare. */ eProsima_user_DllExport bool operator !=( - const Image& x) const; + const CarlaStatus& x) const; /*! * @brief This function copies the value in member header @@ -151,138 +152,100 @@ namespace sensor_msgs { */ eProsima_user_DllExport std_msgs::msg::Header& header(); /*! - * @brief This function sets a value in member height - * @param _height New value for member height + * @brief This function copies the value in member episode_settings + * @param _episode_settings New value to be copied in member episode_settings */ - eProsima_user_DllExport void height( - uint32_t _height); + eProsima_user_DllExport void episode_settings( + const carla_msgs::msg::CarlaEpisodeSettings& _episode_settings); /*! - * @brief This function returns the value of member height - * @return Value of member height + * @brief This function moves the value in member episode_settings + * @param _episode_settings New value to be moved in member episode_settings */ - eProsima_user_DllExport uint32_t height() const; + eProsima_user_DllExport void episode_settings( + carla_msgs::msg::CarlaEpisodeSettings&& _episode_settings); /*! - * @brief This function returns a reference to member height - * @return Reference to member height + * @brief This function returns a constant reference to member episode_settings + * @return Constant reference to member episode_settings */ - eProsima_user_DllExport uint32_t& height(); + eProsima_user_DllExport const carla_msgs::msg::CarlaEpisodeSettings& episode_settings() const; /*! - * @brief This function sets a value in member width - * @param _width New value for member width + * @brief This function returns a reference to member episode_settings + * @return Reference to member episode_settings */ - eProsima_user_DllExport void width( - uint32_t _width); - + eProsima_user_DllExport carla_msgs::msg::CarlaEpisodeSettings& episode_settings(); /*! - * @brief This function returns the value of member width - * @return Value of member width + * @brief This function sets a value in member frame + * @param _frame New value for member frame */ - eProsima_user_DllExport uint32_t width() const; + eProsima_user_DllExport void frame( + uint64_t _frame); /*! - * @brief This function returns a reference to member width - * @return Reference to member width + * @brief This function returns the value of member frame + * @return Value of member frame */ - eProsima_user_DllExport uint32_t& width(); + eProsima_user_DllExport uint64_t frame() const; /*! - * @brief This function copies the value in member encoding - * @param _encoding New value to be copied in member encoding + * @brief This function returns a reference to member frame + * @return Reference to member frame */ - eProsima_user_DllExport void encoding( - const std::string& _encoding); + eProsima_user_DllExport uint64_t& frame(); /*! - * @brief This function moves the value in member encoding - * @param _encoding New value to be moved in member encoding + * @brief This function copies the value in member synchronous_mode_participant_states + * @param _synchronous_mode_participant_states New value to be copied in member synchronous_mode_participant_states */ - eProsima_user_DllExport void encoding( - std::string&& _encoding); + eProsima_user_DllExport void synchronous_mode_participant_states( + const std::vector& _synchronous_mode_participant_states); /*! - * @brief This function returns a constant reference to member encoding - * @return Constant reference to member encoding + * @brief This function moves the value in member synchronous_mode_participant_states + * @param _synchronous_mode_participant_states New value to be moved in member synchronous_mode_participant_states */ - eProsima_user_DllExport const std::string& encoding() const; + eProsima_user_DllExport void synchronous_mode_participant_states( + std::vector&& _synchronous_mode_participant_states); /*! - * @brief This function returns a reference to member encoding - * @return Reference to member encoding + * @brief This function returns a constant reference to member synchronous_mode_participant_states + * @return Constant reference to member synchronous_mode_participant_states */ - eProsima_user_DllExport std::string& encoding(); - /*! - * @brief This function sets a value in member is_bigendian - * @param _is_bigendian New value for member is_bigendian - */ - eProsima_user_DllExport void is_bigendian( - uint8_t _is_bigendian); + eProsima_user_DllExport const std::vector& synchronous_mode_participant_states() const; /*! - * @brief This function returns the value of member is_bigendian - * @return Value of member is_bigendian + * @brief This function returns a reference to member synchronous_mode_participant_states + * @return Reference to member synchronous_mode_participant_states */ - eProsima_user_DllExport uint8_t is_bigendian() const; - + eProsima_user_DllExport std::vector& synchronous_mode_participant_states(); /*! - * @brief This function returns a reference to member is_bigendian - * @return Reference to member is_bigendian + * @brief This function sets a value in member game_running + * @param _game_running New value for member game_running */ - eProsima_user_DllExport uint8_t& is_bigendian(); + eProsima_user_DllExport void game_running( + bool _game_running); /*! - * @brief This function sets a value in member step - * @param _step New value for member step + * @brief This function returns the value of member game_running + * @return Value of member game_running */ - eProsima_user_DllExport void step( - uint32_t _step); + eProsima_user_DllExport bool game_running() const; /*! - * @brief This function returns the value of member step - * @return Value of member step + * @brief This function returns a reference to member game_running + * @return Reference to member game_running */ - eProsima_user_DllExport uint32_t step() const; + eProsima_user_DllExport bool& game_running(); - /*! - * @brief This function returns a reference to member step - * @return Reference to member step - */ - eProsima_user_DllExport uint32_t& step(); - - /*! - * @brief This function copies the value in member data - * @param _data New value to be copied in member data - */ - eProsima_user_DllExport void data( - const std::vector& _data); /*! - * @brief This function moves the value in member data - * @param _data New value to be moved in member data - */ - eProsima_user_DllExport void data( - std::vector&& _data); - - /*! - * @brief This function returns a constant reference to member data - * @return Constant reference to member data - */ - eProsima_user_DllExport const std::vector& data() const; - - /*! - * @brief This function returns a reference to member data - * @return Reference to member data + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. */ - eProsima_user_DllExport std::vector& data(); - - /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -293,7 +256,7 @@ namespace sensor_msgs { * @return Serialized size. */ eProsima_user_DllExport static size_t getCdrSerializedSize( - const sensor_msgs::msg::Image& data, + const carla_msgs::msg::CarlaStatus& data, size_t current_alignment = 0); @@ -311,6 +274,8 @@ namespace sensor_msgs { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -333,15 +298,14 @@ namespace sensor_msgs { eprosima::fastcdr::Cdr& cdr) const; private: + std_msgs::msg::Header m_header; - uint32_t m_height; - uint32_t m_width; - std::string m_encoding; - uint8_t m_is_bigendian; - uint32_t m_step; - std::vector m_data; + carla_msgs::msg::CarlaEpisodeSettings m_episode_settings; + uint64_t m_frame; + std::vector m_synchronous_mode_participant_states; + bool m_game_running; }; } // namespace msg -} // namespace sensor_msgs +} // namespace carla_msgs -#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGE_H_ +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASTATUS_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/PointCloud2PubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatusPubSubTypes.cxx similarity index 69% rename from LibCarla/source/carla/ros2/types/PointCloud2PubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatusPubSubTypes.cxx index d2e39c66dc9..4726108d66c 100644 --- a/LibCarla/source/carla/ros2/types/PointCloud2PubSubTypes.cpp +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatusPubSubTypes.cxx @@ -13,36 +13,37 @@ // limitations under the License. /*! - * @file PointCloud2PubSubTypes.cpp + * @file CarlaStatusPubSubTypes.cpp * This header file contains the implementation of the serialization functions. * * This file was generated by the tool fastcdrgen. */ + #include #include -#include "PointCloud2PubSubTypes.h" +#include "CarlaStatusPubSubTypes.h" using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; -namespace sensor_msgs { +namespace carla_msgs { namespace msg { - PointCloud2PubSubType::PointCloud2PubSubType() + CarlaStatusPubSubType::CarlaStatusPubSubType() { - setName("sensor_msgs::msg::dds_::PointCloud2_"); - auto type_size = PointCloud2::getMaxCdrSerializedSize(); + setName("carla_msgs::msg::dds_::CarlaStatus_"); + auto type_size = CarlaStatus::getMaxCdrSerializedSize(); type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = PointCloud2::isKeyDefined(); - size_t keyLength = PointCloud2::getKeyMaxCdrSerializedSize() > 16 ? - PointCloud2::getKeyMaxCdrSerializedSize() : 16; + m_isGetKeyDefined = CarlaStatus::isKeyDefined(); + size_t keyLength = CarlaStatus::getKeyMaxCdrSerializedSize() > 16 ? + CarlaStatus::getKeyMaxCdrSerializedSize() : 16; m_keyBuffer = reinterpret_cast(malloc(keyLength)); memset(m_keyBuffer, 0, keyLength); } - PointCloud2PubSubType::~PointCloud2PubSubType() + CarlaStatusPubSubType::~CarlaStatusPubSubType() { if (m_keyBuffer != nullptr) { @@ -50,11 +51,11 @@ namespace sensor_msgs { } } - bool PointCloud2PubSubType::serialize( + bool CarlaStatusPubSubType::serialize( void* data, SerializedPayload_t* payload) { - PointCloud2* p_type = static_cast(data); + CarlaStatus* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); @@ -79,25 +80,25 @@ namespace sensor_msgs { return true; } - bool PointCloud2PubSubType::deserialize( + bool CarlaStatusPubSubType::deserialize( SerializedPayload_t* payload, void* data) { - try - { - //Convert DATA to pointer of your type - PointCloud2* p_type = static_cast(data); + //Convert DATA to pointer of your type + CarlaStatus* p_type = static_cast(data); - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); - // Deserialize encapsulation. - deser.read_encapsulation(); - payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + try + { // Deserialize the object. p_type->deserialize(deser); } @@ -109,28 +110,28 @@ namespace sensor_msgs { return true; } - std::function PointCloud2PubSubType::getSerializedSizeProvider( + std::function CarlaStatusPubSubType::getSerializedSizeProvider( void* data) { return [data]() -> uint32_t { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + 4u /*encapsulation*/; }; } - void* PointCloud2PubSubType::createData() + void* CarlaStatusPubSubType::createData() { - return reinterpret_cast(new PointCloud2()); + return reinterpret_cast(new CarlaStatus()); } - void PointCloud2PubSubType::deleteData( + void CarlaStatusPubSubType::deleteData( void* data) { - delete(reinterpret_cast(data)); + delete(reinterpret_cast(data)); } - bool PointCloud2PubSubType::getKey( + bool CarlaStatusPubSubType::getKey( void* data, InstanceHandle_t* handle, bool force_md5) @@ -140,16 +141,16 @@ namespace sensor_msgs { return false; } - PointCloud2* p_type = static_cast(data); + CarlaStatus* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - PointCloud2::getKeyMaxCdrSerializedSize()); + CarlaStatus::getKeyMaxCdrSerializedSize()); // Object that serializes the data. eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); p_type->serializeKey(ser); - if (force_md5 || PointCloud2::getKeyMaxCdrSerializedSize() > 16) + if (force_md5 || CarlaStatus::getKeyMaxCdrSerializedSize() > 16) { m_md5.init(); m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); @@ -168,5 +169,8 @@ namespace sensor_msgs { } return true; } + + } //End of namespace msg -} //End of namespace sensor_msgs + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/types/PointFieldPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatusPubSubTypes.h similarity index 79% rename from LibCarla/source/carla/ros2/types/PointFieldPubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatusPubSubTypes.h index 1ff3d73c430..3ab5acb6ec7 100644 --- a/LibCarla/source/carla/ros2/types/PointFieldPubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatusPubSubTypes.h @@ -13,42 +13,43 @@ // limitations under the License. /*! - * @file PointFieldPubSubTypes.h + * @file CarlaStatusPubSubTypes.h * This header file contains the declaration of the serialization functions. * * This file was generated by the tool fastcdrgen. */ -#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELD_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELD_PUBSUBTYPES_H_ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASTATUS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASTATUS_PUBSUBTYPES_H_ #include #include -#include "PointField.h" +#include "CarlaStatus.h" #if !defined(GEN_API_VER) || (GEN_API_VER != 1) #error \ - Generated PointField is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. + Generated CarlaStatus is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. #endif // GEN_API_VER -namespace sensor_msgs +namespace carla_msgs { namespace msg { /*! - * @brief This class represents the TopicDataType of the type PointField defined by the user in the IDL file. - * @ingroup POINTFIELD + * @brief This class represents the TopicDataType of the type CarlaStatus defined by the user in the IDL file. + * @ingroup CARLASTATUS */ - class PointFieldPubSubType : public eprosima::fastdds::dds::TopicDataType + class CarlaStatusPubSubType : public eprosima::fastdds::dds::TopicDataType { public: - typedef PointField type; + typedef CarlaStatus type; - eProsima_user_DllExport PointFieldPubSubType(); + eProsima_user_DllExport CarlaStatusPubSubType(); - eProsima_user_DllExport virtual ~PointFieldPubSubType() override; + eProsima_user_DllExport virtual ~CarlaStatusPubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -96,10 +97,11 @@ namespace sensor_msgs } #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; unsigned char* m_keyBuffer; }; } } -#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELD_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASTATUS_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindow.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindow.cxx new file mode 100644 index 00000000000..d57a0972039 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindow.cxx @@ -0,0 +1,183 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaSynchronizationWindow.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaSynchronizationWindow.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaSynchronizationWindow::CarlaSynchronizationWindow() +{ + // m_synchronization_window_target_game_time com.eprosima.idl.parser.typecode.PrimitiveTypeCode@6253c26 + m_synchronization_window_target_game_time = 0.0; + +} + +carla_msgs::msg::CarlaSynchronizationWindow::~CarlaSynchronizationWindow() +{ +} + +carla_msgs::msg::CarlaSynchronizationWindow::CarlaSynchronizationWindow( + const CarlaSynchronizationWindow& x) +{ + m_synchronization_window_target_game_time = x.m_synchronization_window_target_game_time; +} + +carla_msgs::msg::CarlaSynchronizationWindow::CarlaSynchronizationWindow( + CarlaSynchronizationWindow&& x) +{ + m_synchronization_window_target_game_time = x.m_synchronization_window_target_game_time; +} + +carla_msgs::msg::CarlaSynchronizationWindow& carla_msgs::msg::CarlaSynchronizationWindow::operator =( + const CarlaSynchronizationWindow& x) +{ + + m_synchronization_window_target_game_time = x.m_synchronization_window_target_game_time; + + return *this; +} + +carla_msgs::msg::CarlaSynchronizationWindow& carla_msgs::msg::CarlaSynchronizationWindow::operator =( + CarlaSynchronizationWindow&& x) +{ + + m_synchronization_window_target_game_time = x.m_synchronization_window_target_game_time; + + return *this; +} + +bool carla_msgs::msg::CarlaSynchronizationWindow::operator ==( + const CarlaSynchronizationWindow& x) const +{ + + return (m_synchronization_window_target_game_time == x.m_synchronization_window_target_game_time); +} + +bool carla_msgs::msg::CarlaSynchronizationWindow::operator !=( + const CarlaSynchronizationWindow& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaSynchronizationWindow::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaSynchronizationWindow::getCdrSerializedSize( + const carla_msgs::msg::CarlaSynchronizationWindow& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaSynchronizationWindow::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_synchronization_window_target_game_time; + +} + +void carla_msgs::msg::CarlaSynchronizationWindow::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_synchronization_window_target_game_time; +} + +/*! + * @brief This function sets a value in member synchronization_window_target_game_time + * @param _synchronization_window_target_game_time New value for member synchronization_window_target_game_time + */ +void carla_msgs::msg::CarlaSynchronizationWindow::synchronization_window_target_game_time( + float _synchronization_window_target_game_time) +{ + m_synchronization_window_target_game_time = _synchronization_window_target_game_time; +} + +/*! + * @brief This function returns the value of member synchronization_window_target_game_time + * @return Value of member synchronization_window_target_game_time + */ +float carla_msgs::msg::CarlaSynchronizationWindow::synchronization_window_target_game_time() const +{ + return m_synchronization_window_target_game_time; +} + +/*! + * @brief This function returns a reference to member synchronization_window_target_game_time + * @return Reference to member synchronization_window_target_game_time + */ +float& carla_msgs::msg::CarlaSynchronizationWindow::synchronization_window_target_game_time() +{ + return m_synchronization_window_target_game_time; +} + + +size_t carla_msgs::msg::CarlaSynchronizationWindow::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaSynchronizationWindow::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaSynchronizationWindow::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindow.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindow.h new file mode 100644 index 00000000000..8288f455158 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindow.h @@ -0,0 +1,210 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaSynchronizationWindow.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOW_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOW_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CarlaSynchronizationWindow_SOURCE) +#define CarlaSynchronizationWindow_DllAPI __declspec( dllexport ) +#else +#define CarlaSynchronizationWindow_DllAPI __declspec( dllimport ) +#endif // CarlaSynchronizationWindow_SOURCE +#else +#define CarlaSynchronizationWindow_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CarlaSynchronizationWindow_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace msg { + /*! + * @brief This class represents the structure CarlaSynchronizationWindow defined by the user in the IDL file. + * @ingroup CARLASYNCHRONIZATIONWINDOW + */ + class CarlaSynchronizationWindow + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaSynchronizationWindow(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaSynchronizationWindow(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaSynchronizationWindow that will be copied. + */ + eProsima_user_DllExport CarlaSynchronizationWindow( + const CarlaSynchronizationWindow& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaSynchronizationWindow that will be copied. + */ + eProsima_user_DllExport CarlaSynchronizationWindow( + CarlaSynchronizationWindow&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaSynchronizationWindow that will be copied. + */ + eProsima_user_DllExport CarlaSynchronizationWindow& operator =( + const CarlaSynchronizationWindow& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaSynchronizationWindow that will be copied. + */ + eProsima_user_DllExport CarlaSynchronizationWindow& operator =( + CarlaSynchronizationWindow&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaSynchronizationWindow object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaSynchronizationWindow& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaSynchronizationWindow object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaSynchronizationWindow& x) const; + + /*! + * @brief This function sets a value in member synchronization_window_target_game_time + * @param _synchronization_window_target_game_time New value for member synchronization_window_target_game_time + */ + eProsima_user_DllExport void synchronization_window_target_game_time( + float _synchronization_window_target_game_time); + + /*! + * @brief This function returns the value of member synchronization_window_target_game_time + * @return Value of member synchronization_window_target_game_time + */ + eProsima_user_DllExport float synchronization_window_target_game_time() const; + + /*! + * @brief This function returns a reference to member synchronization_window_target_game_time + * @return Reference to member synchronization_window_target_game_time + */ + eProsima_user_DllExport float& synchronization_window_target_game_time(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::msg::CarlaSynchronizationWindow& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + float m_synchronization_window_target_game_time; + }; + } // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOW_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantState.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantState.cxx new file mode 100644 index 00000000000..dca5a8bba10 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantState.cxx @@ -0,0 +1,278 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaSynchronizationWindowParticipantState.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaSynchronizationWindowParticipantState.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaSynchronizationWindowParticipantState::CarlaSynchronizationWindowParticipantState() +{ + // m_client_id com.eprosima.idl.parser.typecode.StringTypeCode@506ae4d4 + m_client_id =""; + // m_participant_id com.eprosima.idl.parser.typecode.PrimitiveTypeCode@7d4f9aae + m_participant_id = 0; + // m_target_game_time com.eprosima.idl.parser.typecode.PrimitiveTypeCode@72e5a8e + m_target_game_time = 0.0; + +} + +carla_msgs::msg::CarlaSynchronizationWindowParticipantState::~CarlaSynchronizationWindowParticipantState() +{ + + +} + +carla_msgs::msg::CarlaSynchronizationWindowParticipantState::CarlaSynchronizationWindowParticipantState( + const CarlaSynchronizationWindowParticipantState& x) +{ + m_client_id = x.m_client_id; + m_participant_id = x.m_participant_id; + m_target_game_time = x.m_target_game_time; +} + +carla_msgs::msg::CarlaSynchronizationWindowParticipantState::CarlaSynchronizationWindowParticipantState( + CarlaSynchronizationWindowParticipantState&& x) +{ + m_client_id = std::move(x.m_client_id); + m_participant_id = x.m_participant_id; + m_target_game_time = x.m_target_game_time; +} + +carla_msgs::msg::CarlaSynchronizationWindowParticipantState& carla_msgs::msg::CarlaSynchronizationWindowParticipantState::operator =( + const CarlaSynchronizationWindowParticipantState& x) +{ + + m_client_id = x.m_client_id; + m_participant_id = x.m_participant_id; + m_target_game_time = x.m_target_game_time; + + return *this; +} + +carla_msgs::msg::CarlaSynchronizationWindowParticipantState& carla_msgs::msg::CarlaSynchronizationWindowParticipantState::operator =( + CarlaSynchronizationWindowParticipantState&& x) +{ + + m_client_id = std::move(x.m_client_id); + m_participant_id = x.m_participant_id; + m_target_game_time = x.m_target_game_time; + + return *this; +} + +bool carla_msgs::msg::CarlaSynchronizationWindowParticipantState::operator ==( + const CarlaSynchronizationWindowParticipantState& x) const +{ + + return (m_client_id == x.m_client_id && m_participant_id == x.m_participant_id && m_target_game_time == x.m_target_game_time); +} + +bool carla_msgs::msg::CarlaSynchronizationWindowParticipantState::operator !=( + const CarlaSynchronizationWindowParticipantState& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaSynchronizationWindowParticipantState::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaSynchronizationWindowParticipantState::getCdrSerializedSize( + const carla_msgs::msg::CarlaSynchronizationWindowParticipantState& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.client_id().size() + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaSynchronizationWindowParticipantState::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_client_id; + scdr << m_participant_id; + scdr << m_target_game_time; + +} + +void carla_msgs::msg::CarlaSynchronizationWindowParticipantState::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_client_id; + dcdr >> m_participant_id; + dcdr >> m_target_game_time; +} + +/*! + * @brief This function copies the value in member client_id + * @param _client_id New value to be copied in member client_id + */ +void carla_msgs::msg::CarlaSynchronizationWindowParticipantState::client_id( + const std::string& _client_id) +{ + m_client_id = _client_id; +} + +/*! + * @brief This function moves the value in member client_id + * @param _client_id New value to be moved in member client_id + */ +void carla_msgs::msg::CarlaSynchronizationWindowParticipantState::client_id( + std::string&& _client_id) +{ + m_client_id = std::move(_client_id); +} + +/*! + * @brief This function returns a constant reference to member client_id + * @return Constant reference to member client_id + */ +const std::string& carla_msgs::msg::CarlaSynchronizationWindowParticipantState::client_id() const +{ + return m_client_id; +} + +/*! + * @brief This function returns a reference to member client_id + * @return Reference to member client_id + */ +std::string& carla_msgs::msg::CarlaSynchronizationWindowParticipantState::client_id() +{ + return m_client_id; +} +/*! + * @brief This function sets a value in member participant_id + * @param _participant_id New value for member participant_id + */ +void carla_msgs::msg::CarlaSynchronizationWindowParticipantState::participant_id( + uint32_t _participant_id) +{ + m_participant_id = _participant_id; +} + +/*! + * @brief This function returns the value of member participant_id + * @return Value of member participant_id + */ +uint32_t carla_msgs::msg::CarlaSynchronizationWindowParticipantState::participant_id() const +{ + return m_participant_id; +} + +/*! + * @brief This function returns a reference to member participant_id + * @return Reference to member participant_id + */ +uint32_t& carla_msgs::msg::CarlaSynchronizationWindowParticipantState::participant_id() +{ + return m_participant_id; +} + +/*! + * @brief This function sets a value in member target_game_time + * @param _target_game_time New value for member target_game_time + */ +void carla_msgs::msg::CarlaSynchronizationWindowParticipantState::target_game_time( + double _target_game_time) +{ + m_target_game_time = _target_game_time; +} + +/*! + * @brief This function returns the value of member target_game_time + * @return Value of member target_game_time + */ +double carla_msgs::msg::CarlaSynchronizationWindowParticipantState::target_game_time() const +{ + return m_target_game_time; +} + +/*! + * @brief This function returns a reference to member target_game_time + * @return Reference to member target_game_time + */ +double& carla_msgs::msg::CarlaSynchronizationWindowParticipantState::target_game_time() +{ + return m_target_game_time; +} + + +size_t carla_msgs::msg::CarlaSynchronizationWindowParticipantState::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaSynchronizationWindowParticipantState::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaSynchronizationWindowParticipantState::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantState.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantState.h new file mode 100644 index 00000000000..75431586354 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantState.h @@ -0,0 +1,256 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaSynchronizationWindowParticipantState.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWPARTICIPANTSTATE_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWPARTICIPANTSTATE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CarlaSynchronizationWindowParticipantState_SOURCE) +#define CarlaSynchronizationWindowParticipantState_DllAPI __declspec( dllexport ) +#else +#define CarlaSynchronizationWindowParticipantState_DllAPI __declspec( dllimport ) +#endif // CarlaSynchronizationWindowParticipantState_SOURCE +#else +#define CarlaSynchronizationWindowParticipantState_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CarlaSynchronizationWindowParticipantState_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace msg { + /*! + * @brief This class represents the structure CarlaSynchronizationWindowParticipantState defined by the user in the IDL file. + * @ingroup CARLASYNCHRONIZATIONWINDOWPARTICIPANTSTATE + */ + class CarlaSynchronizationWindowParticipantState + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaSynchronizationWindowParticipantState(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaSynchronizationWindowParticipantState(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaSynchronizationWindowParticipantState that will be copied. + */ + eProsima_user_DllExport CarlaSynchronizationWindowParticipantState( + const CarlaSynchronizationWindowParticipantState& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaSynchronizationWindowParticipantState that will be copied. + */ + eProsima_user_DllExport CarlaSynchronizationWindowParticipantState( + CarlaSynchronizationWindowParticipantState&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaSynchronizationWindowParticipantState that will be copied. + */ + eProsima_user_DllExport CarlaSynchronizationWindowParticipantState& operator =( + const CarlaSynchronizationWindowParticipantState& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaSynchronizationWindowParticipantState that will be copied. + */ + eProsima_user_DllExport CarlaSynchronizationWindowParticipantState& operator =( + CarlaSynchronizationWindowParticipantState&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaSynchronizationWindowParticipantState object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaSynchronizationWindowParticipantState& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaSynchronizationWindowParticipantState object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaSynchronizationWindowParticipantState& x) const; + + /*! + * @brief This function copies the value in member client_id + * @param _client_id New value to be copied in member client_id + */ + eProsima_user_DllExport void client_id( + const std::string& _client_id); + + /*! + * @brief This function moves the value in member client_id + * @param _client_id New value to be moved in member client_id + */ + eProsima_user_DllExport void client_id( + std::string&& _client_id); + + /*! + * @brief This function returns a constant reference to member client_id + * @return Constant reference to member client_id + */ + eProsima_user_DllExport const std::string& client_id() const; + + /*! + * @brief This function returns a reference to member client_id + * @return Reference to member client_id + */ + eProsima_user_DllExport std::string& client_id(); + /*! + * @brief This function sets a value in member participant_id + * @param _participant_id New value for member participant_id + */ + eProsima_user_DllExport void participant_id( + uint32_t _participant_id); + + /*! + * @brief This function returns the value of member participant_id + * @return Value of member participant_id + */ + eProsima_user_DllExport uint32_t participant_id() const; + + /*! + * @brief This function returns a reference to member participant_id + * @return Reference to member participant_id + */ + eProsima_user_DllExport uint32_t& participant_id(); + + /*! + * @brief This function sets a value in member target_game_time + * @param _target_game_time New value for member target_game_time + */ + eProsima_user_DllExport void target_game_time( + double _target_game_time); + + /*! + * @brief This function returns the value of member target_game_time + * @return Value of member target_game_time + */ + eProsima_user_DllExport double target_game_time() const; + + /*! + * @brief This function returns a reference to member target_game_time + * @return Reference to member target_game_time + */ + eProsima_user_DllExport double& target_game_time(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::msg::CarlaSynchronizationWindowParticipantState& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std::string m_client_id; + uint32_t m_participant_id; + double m_target_game_time; + }; + } // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWPARTICIPANTSTATE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantStatePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantStatePubSubTypes.cxx new file mode 100644 index 00000000000..0df7f36926b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantStatePubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaSynchronizationWindowParticipantStatePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaSynchronizationWindowParticipantStatePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaSynchronizationWindowParticipantStatePubSubType::CarlaSynchronizationWindowParticipantStatePubSubType() + { + setName("carla_msgs::msg::dds_::CarlaSynchronizationWindowParticipantState_"); + auto type_size = CarlaSynchronizationWindowParticipantState::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaSynchronizationWindowParticipantState::isKeyDefined(); + size_t keyLength = CarlaSynchronizationWindowParticipantState::getKeyMaxCdrSerializedSize() > 16 ? + CarlaSynchronizationWindowParticipantState::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaSynchronizationWindowParticipantStatePubSubType::~CarlaSynchronizationWindowParticipantStatePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaSynchronizationWindowParticipantStatePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaSynchronizationWindowParticipantState* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaSynchronizationWindowParticipantStatePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaSynchronizationWindowParticipantState* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaSynchronizationWindowParticipantStatePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaSynchronizationWindowParticipantStatePubSubType::createData() + { + return reinterpret_cast(new CarlaSynchronizationWindowParticipantState()); + } + + void CarlaSynchronizationWindowParticipantStatePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaSynchronizationWindowParticipantStatePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaSynchronizationWindowParticipantState* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaSynchronizationWindowParticipantState::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaSynchronizationWindowParticipantState::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantStatePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantStatePubSubTypes.h new file mode 100644 index 00000000000..13850848bc3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantStatePubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaSynchronizationWindowParticipantStatePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWPARTICIPANTSTATE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWPARTICIPANTSTATE_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaSynchronizationWindowParticipantState.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaSynchronizationWindowParticipantState is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CarlaSynchronizationWindowParticipantState defined by the user in the IDL file. + * @ingroup CARLASYNCHRONIZATIONWINDOWPARTICIPANTSTATE + */ + class CarlaSynchronizationWindowParticipantStatePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaSynchronizationWindowParticipantState type; + + eProsima_user_DllExport CarlaSynchronizationWindowParticipantStatePubSubType(); + + eProsima_user_DllExport virtual ~CarlaSynchronizationWindowParticipantStatePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWPARTICIPANTSTATE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowPubSubTypes.cxx new file mode 100644 index 00000000000..f3b17091359 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaSynchronizationWindowPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaSynchronizationWindowPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaSynchronizationWindowPubSubType::CarlaSynchronizationWindowPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaSynchronizationWindow_"); + auto type_size = CarlaSynchronizationWindow::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaSynchronizationWindow::isKeyDefined(); + size_t keyLength = CarlaSynchronizationWindow::getKeyMaxCdrSerializedSize() > 16 ? + CarlaSynchronizationWindow::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaSynchronizationWindowPubSubType::~CarlaSynchronizationWindowPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaSynchronizationWindowPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaSynchronizationWindow* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaSynchronizationWindowPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaSynchronizationWindow* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaSynchronizationWindowPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaSynchronizationWindowPubSubType::createData() + { + return reinterpret_cast(new CarlaSynchronizationWindow()); + } + + void CarlaSynchronizationWindowPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaSynchronizationWindowPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaSynchronizationWindow* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaSynchronizationWindow::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaSynchronizationWindow::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowPubSubTypes.h new file mode 100644 index 00000000000..450288b0418 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaSynchronizationWindowPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOW_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOW_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaSynchronizationWindow.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaSynchronizationWindow is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CarlaSynchronizationWindow defined by the user in the IDL file. + * @ingroup CARLASYNCHRONIZATIONWINDOW + */ + class CarlaSynchronizationWindowPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaSynchronizationWindow type; + + eProsima_user_DllExport CarlaSynchronizationWindowPubSubType(); + + eProsima_user_DllExport virtual ~CarlaSynchronizationWindowPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) CarlaSynchronizationWindow(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOW_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfo.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfo.cxx new file mode 100644 index 00000000000..7f78760d58f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfo.cxx @@ -0,0 +1,281 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaTrafficLightInfo.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaTrafficLightInfo.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaTrafficLightInfo::CarlaTrafficLightInfo() +{ + // m_id com.eprosima.idl.parser.typecode.PrimitiveTypeCode@537f60bf + m_id = 0; + // m_transform com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@5677323c + + // m_trigger_volume com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@18df8434 + + +} + +carla_msgs::msg::CarlaTrafficLightInfo::~CarlaTrafficLightInfo() +{ + + +} + +carla_msgs::msg::CarlaTrafficLightInfo::CarlaTrafficLightInfo( + const CarlaTrafficLightInfo& x) +{ + m_id = x.m_id; + m_transform = x.m_transform; + m_trigger_volume = x.m_trigger_volume; +} + +carla_msgs::msg::CarlaTrafficLightInfo::CarlaTrafficLightInfo( + CarlaTrafficLightInfo&& x) +{ + m_id = x.m_id; + m_transform = std::move(x.m_transform); + m_trigger_volume = std::move(x.m_trigger_volume); +} + +carla_msgs::msg::CarlaTrafficLightInfo& carla_msgs::msg::CarlaTrafficLightInfo::operator =( + const CarlaTrafficLightInfo& x) +{ + + m_id = x.m_id; + m_transform = x.m_transform; + m_trigger_volume = x.m_trigger_volume; + + return *this; +} + +carla_msgs::msg::CarlaTrafficLightInfo& carla_msgs::msg::CarlaTrafficLightInfo::operator =( + CarlaTrafficLightInfo&& x) +{ + + m_id = x.m_id; + m_transform = std::move(x.m_transform); + m_trigger_volume = std::move(x.m_trigger_volume); + + return *this; +} + +bool carla_msgs::msg::CarlaTrafficLightInfo::operator ==( + const CarlaTrafficLightInfo& x) const +{ + + return (m_id == x.m_id && m_transform == x.m_transform && m_trigger_volume == x.m_trigger_volume); +} + +bool carla_msgs::msg::CarlaTrafficLightInfo::operator !=( + const CarlaTrafficLightInfo& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaTrafficLightInfo::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += geometry_msgs::msg::Pose::getMaxCdrSerializedSize(current_alignment); + current_alignment += carla_msgs::msg::CarlaBoundingBox::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaTrafficLightInfo::getCdrSerializedSize( + const carla_msgs::msg::CarlaTrafficLightInfo& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += geometry_msgs::msg::Pose::getCdrSerializedSize(data.transform(), current_alignment); + current_alignment += carla_msgs::msg::CarlaBoundingBox::getCdrSerializedSize(data.trigger_volume(), current_alignment); + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaTrafficLightInfo::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_id; + scdr << m_transform; + scdr << m_trigger_volume; + +} + +void carla_msgs::msg::CarlaTrafficLightInfo::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_id; + dcdr >> m_transform; + dcdr >> m_trigger_volume; +} + +/*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ +void carla_msgs::msg::CarlaTrafficLightInfo::id( + uint32_t _id) +{ + m_id = _id; +} + +/*! + * @brief This function returns the value of member id + * @return Value of member id + */ +uint32_t carla_msgs::msg::CarlaTrafficLightInfo::id() const +{ + return m_id; +} + +/*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ +uint32_t& carla_msgs::msg::CarlaTrafficLightInfo::id() +{ + return m_id; +} + +/*! + * @brief This function copies the value in member transform + * @param _transform New value to be copied in member transform + */ +void carla_msgs::msg::CarlaTrafficLightInfo::transform( + const geometry_msgs::msg::Pose& _transform) +{ + m_transform = _transform; +} + +/*! + * @brief This function moves the value in member transform + * @param _transform New value to be moved in member transform + */ +void carla_msgs::msg::CarlaTrafficLightInfo::transform( + geometry_msgs::msg::Pose&& _transform) +{ + m_transform = std::move(_transform); +} + +/*! + * @brief This function returns a constant reference to member transform + * @return Constant reference to member transform + */ +const geometry_msgs::msg::Pose& carla_msgs::msg::CarlaTrafficLightInfo::transform() const +{ + return m_transform; +} + +/*! + * @brief This function returns a reference to member transform + * @return Reference to member transform + */ +geometry_msgs::msg::Pose& carla_msgs::msg::CarlaTrafficLightInfo::transform() +{ + return m_transform; +} +/*! + * @brief This function copies the value in member trigger_volume + * @param _trigger_volume New value to be copied in member trigger_volume + */ +void carla_msgs::msg::CarlaTrafficLightInfo::trigger_volume( + const carla_msgs::msg::CarlaBoundingBox& _trigger_volume) +{ + m_trigger_volume = _trigger_volume; +} + +/*! + * @brief This function moves the value in member trigger_volume + * @param _trigger_volume New value to be moved in member trigger_volume + */ +void carla_msgs::msg::CarlaTrafficLightInfo::trigger_volume( + carla_msgs::msg::CarlaBoundingBox&& _trigger_volume) +{ + m_trigger_volume = std::move(_trigger_volume); +} + +/*! + * @brief This function returns a constant reference to member trigger_volume + * @return Constant reference to member trigger_volume + */ +const carla_msgs::msg::CarlaBoundingBox& carla_msgs::msg::CarlaTrafficLightInfo::trigger_volume() const +{ + return m_trigger_volume; +} + +/*! + * @brief This function returns a reference to member trigger_volume + * @return Reference to member trigger_volume + */ +carla_msgs::msg::CarlaBoundingBox& carla_msgs::msg::CarlaTrafficLightInfo::trigger_volume() +{ + return m_trigger_volume; +} + +size_t carla_msgs::msg::CarlaTrafficLightInfo::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaTrafficLightInfo::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaTrafficLightInfo::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/types/PointField.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfo.h similarity index 50% rename from LibCarla/source/carla/ros2/types/PointField.h rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfo.h index 16be2f69924..59ad95bf143 100644 --- a/LibCarla/source/carla/ros2/types/PointField.h +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfo.h @@ -13,16 +13,17 @@ // limitations under the License. /*! - * @file PointField.h + * @file CarlaTrafficLightInfo.h * This header file contains the declaration of the described types in the IDL file. * * This file was generated by the tool gen. */ -#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELD_H_ -#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELD_H_ +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFO_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFO_H_ -#include +#include "CarlaBoundingBox.h" +#include "geometry_msgs/msg/Pose.h" #include #include @@ -43,16 +44,16 @@ #if defined(_WIN32) #if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(PointField_SOURCE) -#define PointField_DllAPI __declspec( dllexport ) +#if defined(CarlaTrafficLightInfo_SOURCE) +#define CarlaTrafficLightInfo_DllAPI __declspec( dllexport ) #else -#define PointField_DllAPI __declspec( dllimport ) -#endif // PointField_SOURCE +#define CarlaTrafficLightInfo_DllAPI __declspec( dllimport ) +#endif // CarlaTrafficLightInfo_SOURCE #else -#define PointField_DllAPI +#define CarlaTrafficLightInfo_DllAPI #endif // EPROSIMA_USER_DLL_EXPORT #else -#define PointField_DllAPI +#define CarlaTrafficLightInfo_DllAPI #endif // _WIN32 namespace eprosima { @@ -61,165 +62,145 @@ class Cdr; } // namespace fastcdr } // namespace eprosima -namespace sensor_msgs { - namespace msg { - const uint8_t PointField__INT8 = 1; - const uint8_t PointField__UINT8 = 2; - const uint8_t PointField__INT16 = 3; - const uint8_t PointField__UINT16 = 4; - const uint8_t PointField__INT32 = 5; - const uint8_t PointField__UINT32 = 6; - const uint8_t PointField__FLOAT32 = 7; - const uint8_t PointField__FLOAT64 = 8; +namespace carla_msgs { + namespace msg { /*! - * @brief This class represents the structure PointField defined by the user in the IDL file. - * @ingroup POINTFIELD + * @brief This class represents the structure CarlaTrafficLightInfo defined by the user in the IDL file. + * @ingroup CARLATRAFFICLIGHTINFO */ - class PointField + class CarlaTrafficLightInfo { public: /*! * @brief Default constructor. */ - eProsima_user_DllExport PointField(); + eProsima_user_DllExport CarlaTrafficLightInfo(); /*! * @brief Default destructor. */ - eProsima_user_DllExport ~PointField(); + eProsima_user_DllExport ~CarlaTrafficLightInfo(); /*! * @brief Copy constructor. - * @param x Reference to the object sensor_msgs::msg::PointField that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightInfo that will be copied. */ - eProsima_user_DllExport PointField( - const PointField& x); + eProsima_user_DllExport CarlaTrafficLightInfo( + const CarlaTrafficLightInfo& x); /*! * @brief Move constructor. - * @param x Reference to the object sensor_msgs::msg::PointField that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightInfo that will be copied. */ - eProsima_user_DllExport PointField( - PointField&& x) noexcept; + eProsima_user_DllExport CarlaTrafficLightInfo( + CarlaTrafficLightInfo&& x); /*! * @brief Copy assignment. - * @param x Reference to the object sensor_msgs::msg::PointField that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightInfo that will be copied. */ - eProsima_user_DllExport PointField& operator =( - const PointField& x); + eProsima_user_DllExport CarlaTrafficLightInfo& operator =( + const CarlaTrafficLightInfo& x); /*! * @brief Move assignment. - * @param x Reference to the object sensor_msgs::msg::PointField that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightInfo that will be copied. */ - eProsima_user_DllExport PointField& operator =( - PointField&& x) noexcept; + eProsima_user_DllExport CarlaTrafficLightInfo& operator =( + CarlaTrafficLightInfo&& x); /*! * @brief Comparison operator. - * @param x sensor_msgs::msg::PointField object to compare. + * @param x carla_msgs::msg::CarlaTrafficLightInfo object to compare. */ eProsima_user_DllExport bool operator ==( - const PointField& x) const; + const CarlaTrafficLightInfo& x) const; /*! * @brief Comparison operator. - * @param x sensor_msgs::msg::PointField object to compare. + * @param x carla_msgs::msg::CarlaTrafficLightInfo object to compare. */ eProsima_user_DllExport bool operator !=( - const PointField& x) const; + const CarlaTrafficLightInfo& x) const; /*! - * @brief This function copies the value in member name - * @param _name New value to be copied in member name + * @brief This function sets a value in member id + * @param _id New value for member id */ - eProsima_user_DllExport void name( - const std::string& _name); + eProsima_user_DllExport void id( + uint32_t _id); /*! - * @brief This function moves the value in member name - * @param _name New value to be moved in member name + * @brief This function returns the value of member id + * @return Value of member id */ - eProsima_user_DllExport void name( - std::string&& _name); + eProsima_user_DllExport uint32_t id() const; /*! - * @brief This function returns a constant reference to member name - * @return Constant reference to member name + * @brief This function returns a reference to member id + * @return Reference to member id */ - eProsima_user_DllExport const std::string& name() const; + eProsima_user_DllExport uint32_t& id(); /*! - * @brief This function returns a reference to member name - * @return Reference to member name - */ - eProsima_user_DllExport std::string& name(); - /*! - * @brief This function sets a value in member offset - * @param _offset New value for member offset + * @brief This function copies the value in member transform + * @param _transform New value to be copied in member transform */ - eProsima_user_DllExport void offset( - uint32_t _offset); + eProsima_user_DllExport void transform( + const geometry_msgs::msg::Pose& _transform); /*! - * @brief This function returns the value of member offset - * @return Value of member offset + * @brief This function moves the value in member transform + * @param _transform New value to be moved in member transform */ - eProsima_user_DllExport uint32_t offset() const; + eProsima_user_DllExport void transform( + geometry_msgs::msg::Pose&& _transform); /*! - * @brief This function returns a reference to member offset - * @return Reference to member offset + * @brief This function returns a constant reference to member transform + * @return Constant reference to member transform */ - eProsima_user_DllExport uint32_t& offset(); + eProsima_user_DllExport const geometry_msgs::msg::Pose& transform() const; /*! - * @brief This function sets a value in member datatype - * @param _datatype New value for member datatype + * @brief This function returns a reference to member transform + * @return Reference to member transform */ - eProsima_user_DllExport void datatype( - uint8_t _datatype); - + eProsima_user_DllExport geometry_msgs::msg::Pose& transform(); /*! - * @brief This function returns the value of member datatype - * @return Value of member datatype + * @brief This function copies the value in member trigger_volume + * @param _trigger_volume New value to be copied in member trigger_volume */ - eProsima_user_DllExport uint8_t datatype() const; + eProsima_user_DllExport void trigger_volume( + const carla_msgs::msg::CarlaBoundingBox& _trigger_volume); /*! - * @brief This function returns a reference to member datatype - * @return Reference to member datatype + * @brief This function moves the value in member trigger_volume + * @param _trigger_volume New value to be moved in member trigger_volume */ - eProsima_user_DllExport uint8_t& datatype(); + eProsima_user_DllExport void trigger_volume( + carla_msgs::msg::CarlaBoundingBox&& _trigger_volume); /*! - * @brief This function sets a value in member count - * @param _count New value for member count + * @brief This function returns a constant reference to member trigger_volume + * @return Constant reference to member trigger_volume */ - eProsima_user_DllExport void count( - uint32_t _count); + eProsima_user_DllExport const carla_msgs::msg::CarlaBoundingBox& trigger_volume() const; /*! - * @brief This function returns the value of member count - * @return Value of member count + * @brief This function returns a reference to member trigger_volume + * @return Reference to member trigger_volume */ - eProsima_user_DllExport uint32_t count() const; + eProsima_user_DllExport carla_msgs::msg::CarlaBoundingBox& trigger_volume(); /*! - * @brief This function returns a reference to member count - * @return Reference to member count + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. */ - eProsima_user_DllExport uint32_t& count(); - - /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -230,9 +211,10 @@ namespace sensor_msgs { * @return Serialized size. */ eProsima_user_DllExport static size_t getCdrSerializedSize( - const sensor_msgs::msg::PointField& data, + const carla_msgs::msg::CarlaTrafficLightInfo& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -247,6 +229,8 @@ namespace sensor_msgs { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -269,13 +253,12 @@ namespace sensor_msgs { eprosima::fastcdr::Cdr& cdr) const; private: - std::string m_name; - uint32_t m_offset; - uint8_t m_datatype; - uint32_t m_count; + uint32_t m_id; + geometry_msgs::msg::Pose m_transform; + carla_msgs::msg::CarlaBoundingBox m_trigger_volume; }; } // namespace msg -} // namespace sensor_msgs +} // namespace carla_msgs -#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELD_H_ +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFO_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoList.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoList.cxx new file mode 100644 index 00000000000..b93a7c0f417 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoList.cxx @@ -0,0 +1,198 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaTrafficLightInfoList.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaTrafficLightInfoList.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaTrafficLightInfoList::CarlaTrafficLightInfoList() +{ + // m_traffic_lights com.eprosima.idl.parser.typecode.SequenceTypeCode@2892d68 + + +} + +carla_msgs::msg::CarlaTrafficLightInfoList::~CarlaTrafficLightInfoList() +{ +} + +carla_msgs::msg::CarlaTrafficLightInfoList::CarlaTrafficLightInfoList( + const CarlaTrafficLightInfoList& x) +{ + m_traffic_lights = x.m_traffic_lights; +} + +carla_msgs::msg::CarlaTrafficLightInfoList::CarlaTrafficLightInfoList( + CarlaTrafficLightInfoList&& x) +{ + m_traffic_lights = std::move(x.m_traffic_lights); +} + +carla_msgs::msg::CarlaTrafficLightInfoList& carla_msgs::msg::CarlaTrafficLightInfoList::operator =( + const CarlaTrafficLightInfoList& x) +{ + + m_traffic_lights = x.m_traffic_lights; + + return *this; +} + +carla_msgs::msg::CarlaTrafficLightInfoList& carla_msgs::msg::CarlaTrafficLightInfoList::operator =( + CarlaTrafficLightInfoList&& x) +{ + + m_traffic_lights = std::move(x.m_traffic_lights); + + return *this; +} + +bool carla_msgs::msg::CarlaTrafficLightInfoList::operator ==( + const CarlaTrafficLightInfoList& x) const +{ + + return (m_traffic_lights == x.m_traffic_lights); +} + +bool carla_msgs::msg::CarlaTrafficLightInfoList::operator !=( + const CarlaTrafficLightInfoList& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaTrafficLightInfoList::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < 100; ++a) + { + current_alignment += carla_msgs::msg::CarlaTrafficLightInfo::getMaxCdrSerializedSize(current_alignment);} + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaTrafficLightInfoList::getCdrSerializedSize( + const carla_msgs::msg::CarlaTrafficLightInfoList& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < data.traffic_lights().size(); ++a) + { + current_alignment += carla_msgs::msg::CarlaTrafficLightInfo::getCdrSerializedSize(data.traffic_lights().at(a), current_alignment);} + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaTrafficLightInfoList::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_traffic_lights; +} + +void carla_msgs::msg::CarlaTrafficLightInfoList::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_traffic_lights;} + +/*! + * @brief This function copies the value in member traffic_lights + * @param _traffic_lights New value to be copied in member traffic_lights + */ +void carla_msgs::msg::CarlaTrafficLightInfoList::traffic_lights( + const std::vector& _traffic_lights) +{ + m_traffic_lights = _traffic_lights; +} + +/*! + * @brief This function moves the value in member traffic_lights + * @param _traffic_lights New value to be moved in member traffic_lights + */ +void carla_msgs::msg::CarlaTrafficLightInfoList::traffic_lights( + std::vector&& _traffic_lights) +{ + m_traffic_lights = std::move(_traffic_lights); +} + +/*! + * @brief This function returns a constant reference to member traffic_lights + * @return Constant reference to member traffic_lights + */ +const std::vector& carla_msgs::msg::CarlaTrafficLightInfoList::traffic_lights() const +{ + return m_traffic_lights; +} + +/*! + * @brief This function returns a reference to member traffic_lights + * @return Reference to member traffic_lights + */ +std::vector& carla_msgs::msg::CarlaTrafficLightInfoList::traffic_lights() +{ + return m_traffic_lights; +} + +size_t carla_msgs::msg::CarlaTrafficLightInfoList::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaTrafficLightInfoList::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaTrafficLightInfoList::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoList.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoList.h new file mode 100644 index 00000000000..63598e361b2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoList.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaTrafficLightInfoList.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOLIST_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOLIST_H_ + +#include "CarlaTrafficLightInfo.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CarlaTrafficLightInfoList_SOURCE) +#define CarlaTrafficLightInfoList_DllAPI __declspec( dllexport ) +#else +#define CarlaTrafficLightInfoList_DllAPI __declspec( dllimport ) +#endif // CarlaTrafficLightInfoList_SOURCE +#else +#define CarlaTrafficLightInfoList_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CarlaTrafficLightInfoList_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace msg { + /*! + * @brief This class represents the structure CarlaTrafficLightInfoList defined by the user in the IDL file. + * @ingroup CARLATRAFFICLIGHTINFOLIST + */ + class CarlaTrafficLightInfoList + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaTrafficLightInfoList(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaTrafficLightInfoList(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightInfoList that will be copied. + */ + eProsima_user_DllExport CarlaTrafficLightInfoList( + const CarlaTrafficLightInfoList& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightInfoList that will be copied. + */ + eProsima_user_DllExport CarlaTrafficLightInfoList( + CarlaTrafficLightInfoList&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightInfoList that will be copied. + */ + eProsima_user_DllExport CarlaTrafficLightInfoList& operator =( + const CarlaTrafficLightInfoList& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightInfoList that will be copied. + */ + eProsima_user_DllExport CarlaTrafficLightInfoList& operator =( + CarlaTrafficLightInfoList&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaTrafficLightInfoList object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaTrafficLightInfoList& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaTrafficLightInfoList object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaTrafficLightInfoList& x) const; + + /*! + * @brief This function copies the value in member traffic_lights + * @param _traffic_lights New value to be copied in member traffic_lights + */ + eProsima_user_DllExport void traffic_lights( + const std::vector& _traffic_lights); + + /*! + * @brief This function moves the value in member traffic_lights + * @param _traffic_lights New value to be moved in member traffic_lights + */ + eProsima_user_DllExport void traffic_lights( + std::vector&& _traffic_lights); + + /*! + * @brief This function returns a constant reference to member traffic_lights + * @return Constant reference to member traffic_lights + */ + eProsima_user_DllExport const std::vector& traffic_lights() const; + + /*! + * @brief This function returns a reference to member traffic_lights + * @return Reference to member traffic_lights + */ + eProsima_user_DllExport std::vector& traffic_lights(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::msg::CarlaTrafficLightInfoList& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std::vector m_traffic_lights; + }; + } // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOLIST_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoListPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoListPubSubTypes.cxx new file mode 100644 index 00000000000..c2ac4109ae0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoListPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaTrafficLightInfoListPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaTrafficLightInfoListPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaTrafficLightInfoListPubSubType::CarlaTrafficLightInfoListPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaTrafficLightInfoList_"); + auto type_size = CarlaTrafficLightInfoList::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaTrafficLightInfoList::isKeyDefined(); + size_t keyLength = CarlaTrafficLightInfoList::getKeyMaxCdrSerializedSize() > 16 ? + CarlaTrafficLightInfoList::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaTrafficLightInfoListPubSubType::~CarlaTrafficLightInfoListPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaTrafficLightInfoListPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaTrafficLightInfoList* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaTrafficLightInfoListPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaTrafficLightInfoList* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaTrafficLightInfoListPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaTrafficLightInfoListPubSubType::createData() + { + return reinterpret_cast(new CarlaTrafficLightInfoList()); + } + + void CarlaTrafficLightInfoListPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaTrafficLightInfoListPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaTrafficLightInfoList* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaTrafficLightInfoList::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaTrafficLightInfoList::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoListPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoListPubSubTypes.h new file mode 100644 index 00000000000..e6b2ebe2ca6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoListPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaTrafficLightInfoListPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOLIST_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOLIST_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaTrafficLightInfoList.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaTrafficLightInfoList is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CarlaTrafficLightInfoList defined by the user in the IDL file. + * @ingroup CARLATRAFFICLIGHTINFOLIST + */ + class CarlaTrafficLightInfoListPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaTrafficLightInfoList type; + + eProsima_user_DllExport CarlaTrafficLightInfoListPubSubType(); + + eProsima_user_DllExport virtual ~CarlaTrafficLightInfoListPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOLIST_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoPubSubTypes.cxx new file mode 100644 index 00000000000..d371004b517 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaTrafficLightInfoPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaTrafficLightInfoPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaTrafficLightInfoPubSubType::CarlaTrafficLightInfoPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaTrafficLightInfo_"); + auto type_size = CarlaTrafficLightInfo::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaTrafficLightInfo::isKeyDefined(); + size_t keyLength = CarlaTrafficLightInfo::getKeyMaxCdrSerializedSize() > 16 ? + CarlaTrafficLightInfo::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaTrafficLightInfoPubSubType::~CarlaTrafficLightInfoPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaTrafficLightInfoPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaTrafficLightInfo* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaTrafficLightInfoPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaTrafficLightInfo* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaTrafficLightInfoPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaTrafficLightInfoPubSubType::createData() + { + return reinterpret_cast(new CarlaTrafficLightInfo()); + } + + void CarlaTrafficLightInfoPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaTrafficLightInfoPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaTrafficLightInfo* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaTrafficLightInfo::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaTrafficLightInfo::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoPubSubTypes.h new file mode 100644 index 00000000000..8bbaff04a96 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaTrafficLightInfoPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFO_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFO_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaTrafficLightInfo.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaTrafficLightInfo is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CarlaTrafficLightInfo defined by the user in the IDL file. + * @ingroup CARLATRAFFICLIGHTINFO + */ + class CarlaTrafficLightInfoPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaTrafficLightInfo type; + + eProsima_user_DllExport CarlaTrafficLightInfoPubSubType(); + + eProsima_user_DllExport virtual ~CarlaTrafficLightInfoPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) CarlaTrafficLightInfo(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFO_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatus.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatus.cxx new file mode 100644 index 00000000000..ea75e0b0c95 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatus.cxx @@ -0,0 +1,282 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaTrafficLightStatus.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaTrafficLightStatus.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + +carla_msgs::msg::CarlaTrafficLightStatus::CarlaTrafficLightStatus() +{ + // m_header com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@7674f035 + + // m_id com.eprosima.idl.parser.typecode.PrimitiveTypeCode@69e153c5 + m_id = 0; + // m_state com.eprosima.idl.parser.typecode.PrimitiveTypeCode@173ed316 + m_state = 0; + +} + +carla_msgs::msg::CarlaTrafficLightStatus::~CarlaTrafficLightStatus() +{ + + +} + +carla_msgs::msg::CarlaTrafficLightStatus::CarlaTrafficLightStatus( + const CarlaTrafficLightStatus& x) +{ + m_header = x.m_header; + m_id = x.m_id; + m_state = x.m_state; +} + +carla_msgs::msg::CarlaTrafficLightStatus::CarlaTrafficLightStatus( + CarlaTrafficLightStatus&& x) +{ + m_header = std::move(x.m_header); + m_id = x.m_id; + m_state = x.m_state; +} + +carla_msgs::msg::CarlaTrafficLightStatus& carla_msgs::msg::CarlaTrafficLightStatus::operator =( + const CarlaTrafficLightStatus& x) +{ + + m_header = x.m_header; + m_id = x.m_id; + m_state = x.m_state; + + return *this; +} + +carla_msgs::msg::CarlaTrafficLightStatus& carla_msgs::msg::CarlaTrafficLightStatus::operator =( + CarlaTrafficLightStatus&& x) +{ + + m_header = std::move(x.m_header); + m_id = x.m_id; + m_state = x.m_state; + + return *this; +} + +bool carla_msgs::msg::CarlaTrafficLightStatus::operator ==( + const CarlaTrafficLightStatus& x) const +{ + + return (m_header == x.m_header && m_id == x.m_id && m_state == x.m_state); +} + +bool carla_msgs::msg::CarlaTrafficLightStatus::operator !=( + const CarlaTrafficLightStatus& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaTrafficLightStatus::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getMaxCdrSerializedSize(current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaTrafficLightStatus::getCdrSerializedSize( + const carla_msgs::msg::CarlaTrafficLightStatus& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getCdrSerializedSize(data.header(), current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaTrafficLightStatus::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_header; + scdr << m_id; + scdr << m_state; + +} + +void carla_msgs::msg::CarlaTrafficLightStatus::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_header; + dcdr >> m_id; + dcdr >> m_state; +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void carla_msgs::msg::CarlaTrafficLightStatus::header( + const std_msgs::msg::Header& _header) +{ + m_header = _header; +} + +/*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ +void carla_msgs::msg::CarlaTrafficLightStatus::header( + std_msgs::msg::Header&& _header) +{ + m_header = std::move(_header); +} + +/*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ +const std_msgs::msg::Header& carla_msgs::msg::CarlaTrafficLightStatus::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& carla_msgs::msg::CarlaTrafficLightStatus::header() +{ + return m_header; +} +/*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ +void carla_msgs::msg::CarlaTrafficLightStatus::id( + uint32_t _id) +{ + m_id = _id; +} + +/*! + * @brief This function returns the value of member id + * @return Value of member id + */ +uint32_t carla_msgs::msg::CarlaTrafficLightStatus::id() const +{ + return m_id; +} + +/*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ +uint32_t& carla_msgs::msg::CarlaTrafficLightStatus::id() +{ + return m_id; +} + +/*! + * @brief This function sets a value in member state + * @param _state New value for member state + */ +void carla_msgs::msg::CarlaTrafficLightStatus::state( + uint8_t _state) +{ + m_state = _state; +} + +/*! + * @brief This function returns the value of member state + * @return Value of member state + */ +uint8_t carla_msgs::msg::CarlaTrafficLightStatus::state() const +{ + return m_state; +} + +/*! + * @brief This function returns a reference to member state + * @return Reference to member state + */ +uint8_t& carla_msgs::msg::CarlaTrafficLightStatus::state() +{ + return m_state; +} + + +size_t carla_msgs::msg::CarlaTrafficLightStatus::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaTrafficLightStatus::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaTrafficLightStatus::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/types/Odometry.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatus.h similarity index 52% rename from LibCarla/source/carla/ros2/types/Odometry.h rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatus.h index fe33619e665..c96d050333c 100644 --- a/LibCarla/source/carla/ros2/types/Odometry.h +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatus.h @@ -13,20 +13,16 @@ // limitations under the License. /*! - * @file Odometry.h + * @file CarlaTrafficLightStatus.h * This header file contains the declaration of the described types in the IDL file. * * This file was generated by the tool gen. */ -#ifndef _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRY_H_ -#define _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRY_H_ +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUS_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUS_H_ -#include "PoseWithCovariance.h" -#include "TwistWithCovariance.h" -#include "Header.h" - -#include +#include "std_msgs/msg/Header.h" #include #include @@ -47,16 +43,16 @@ #if defined(_WIN32) #if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(Odometry_SOURCE) -#define Odometry_DllAPI __declspec( dllexport ) +#if defined(CarlaTrafficLightStatus_SOURCE) +#define CarlaTrafficLightStatus_DllAPI __declspec( dllexport ) #else -#define Odometry_DllAPI __declspec( dllimport ) -#endif // Odometry_SOURCE +#define CarlaTrafficLightStatus_DllAPI __declspec( dllimport ) +#endif // CarlaTrafficLightStatus_SOURCE #else -#define Odometry_DllAPI +#define CarlaTrafficLightStatus_DllAPI #endif // EPROSIMA_USER_DLL_EXPORT #else -#define Odometry_DllAPI +#define CarlaTrafficLightStatus_DllAPI #endif // _WIN32 namespace eprosima { @@ -65,67 +61,75 @@ class Cdr; } // namespace fastcdr } // namespace eprosima -namespace nav_msgs { + +namespace carla_msgs { namespace msg { + namespace CarlaTrafficLightStatus_Constants { + const uint8_t RED = 0; + const uint8_t YELLOW = 1; + const uint8_t GREEN = 2; + const uint8_t OFF = 3; + const uint8_t UNKNOWN = 4; + } // namespace CarlaTrafficLightStatus_Constants /*! - * @brief This class represents the structure Odometry defined by the user in the IDL file. - * @ingroup ODOMETRY + * @brief This class represents the structure CarlaTrafficLightStatus defined by the user in the IDL file. + * @ingroup CARLATRAFFICLIGHTSTATUS */ - class Odometry + class CarlaTrafficLightStatus { public: /*! * @brief Default constructor. */ - eProsima_user_DllExport Odometry(); + eProsima_user_DllExport CarlaTrafficLightStatus(); /*! * @brief Default destructor. */ - eProsima_user_DllExport ~Odometry(); + eProsima_user_DllExport ~CarlaTrafficLightStatus(); /*! * @brief Copy constructor. - * @param x Reference to the object nav_msgs::msg::Odometry that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightStatus that will be copied. */ - eProsima_user_DllExport Odometry( - const Odometry& x); + eProsima_user_DllExport CarlaTrafficLightStatus( + const CarlaTrafficLightStatus& x); /*! * @brief Move constructor. - * @param x Reference to the object nav_msgs::msg::Odometry that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightStatus that will be copied. */ - eProsima_user_DllExport Odometry( - Odometry&& x) noexcept; + eProsima_user_DllExport CarlaTrafficLightStatus( + CarlaTrafficLightStatus&& x); /*! * @brief Copy assignment. - * @param x Reference to the object nav_msgs::msg::Odometry that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightStatus that will be copied. */ - eProsima_user_DllExport Odometry& operator =( - const Odometry& x); + eProsima_user_DllExport CarlaTrafficLightStatus& operator =( + const CarlaTrafficLightStatus& x); /*! * @brief Move assignment. - * @param x Reference to the object nav_msgs::msg::Odometry that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightStatus that will be copied. */ - eProsima_user_DllExport Odometry& operator =( - Odometry&& x) noexcept; + eProsima_user_DllExport CarlaTrafficLightStatus& operator =( + CarlaTrafficLightStatus&& x); /*! * @brief Comparison operator. - * @param x nav_msgs::msg::Odometry object to compare. + * @param x carla_msgs::msg::CarlaTrafficLightStatus object to compare. */ eProsima_user_DllExport bool operator ==( - const Odometry& x) const; + const CarlaTrafficLightStatus& x) const; /*! * @brief Comparison operator. - * @param x nav_msgs::msg::Odometry object to compare. + * @param x carla_msgs::msg::CarlaTrafficLightStatus object to compare. */ eProsima_user_DllExport bool operator !=( - const Odometry& x) const; + const CarlaTrafficLightStatus& x) const; /*! * @brief This function copies the value in member header @@ -153,87 +157,50 @@ namespace nav_msgs { */ eProsima_user_DllExport std_msgs::msg::Header& header(); /*! - * @brief This function copies the value in member child_frame_id - * @param _child_frame_id New value to be copied in member child_frame_id - */ - eProsima_user_DllExport void child_frame_id( - const std::string& _child_frame_id); - - /*! - * @brief This function moves the value in member child_frame_id - * @param _child_frame_id New value to be moved in member child_frame_id + * @brief This function sets a value in member id + * @param _id New value for member id */ - eProsima_user_DllExport void child_frame_id( - std::string&& _child_frame_id); + eProsima_user_DllExport void id( + uint32_t _id); /*! - * @brief This function returns a constant reference to member child_frame_id - * @return Constant reference to member child_frame_id + * @brief This function returns the value of member id + * @return Value of member id */ - eProsima_user_DllExport const std::string& child_frame_id() const; + eProsima_user_DllExport uint32_t id() const; /*! - * @brief This function returns a reference to member child_frame_id - * @return Reference to member child_frame_id - */ - eProsima_user_DllExport std::string& child_frame_id(); - /*! - * @brief This function copies the value in member pose - * @param _pose New value to be copied in member pose + * @brief This function returns a reference to member id + * @return Reference to member id */ - eProsima_user_DllExport void pose( - const geometry_msgs::msg::PoseWithCovariance& _pose); + eProsima_user_DllExport uint32_t& id(); /*! - * @brief This function moves the value in member pose - * @param _pose New value to be moved in member pose + * @brief This function sets a value in member state + * @param _state New value for member state */ - eProsima_user_DllExport void pose( - geometry_msgs::msg::PoseWithCovariance&& _pose); + eProsima_user_DllExport void state( + uint8_t _state); /*! - * @brief This function returns a constant reference to member pose - * @return Constant reference to member pose + * @brief This function returns the value of member state + * @return Value of member state */ - eProsima_user_DllExport const geometry_msgs::msg::PoseWithCovariance& pose() const; + eProsima_user_DllExport uint8_t state() const; /*! - * @brief This function returns a reference to member pose - * @return Reference to member pose - */ - eProsima_user_DllExport geometry_msgs::msg::PoseWithCovariance& pose(); - /*! - * @brief This function copies the value in member twist - * @param _twist New value to be copied in member twist + * @brief This function returns a reference to member state + * @return Reference to member state */ - eProsima_user_DllExport void twist( - const geometry_msgs::msg::TwistWithCovariance& _twist); + eProsima_user_DllExport uint8_t& state(); - /*! - * @brief This function moves the value in member twist - * @param _twist New value to be moved in member twist - */ - eProsima_user_DllExport void twist( - geometry_msgs::msg::TwistWithCovariance&& _twist); /*! - * @brief This function returns a constant reference to member twist - * @return Constant reference to member twist - */ - eProsima_user_DllExport const geometry_msgs::msg::TwistWithCovariance& twist() const; - - /*! - * @brief This function returns a reference to member twist - * @return Reference to member twist + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. */ - eProsima_user_DllExport geometry_msgs::msg::TwistWithCovariance& twist(); - - /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -244,9 +211,10 @@ namespace nav_msgs { * @return Serialized size. */ eProsima_user_DllExport static size_t getCdrSerializedSize( - const nav_msgs::msg::Odometry& data, + const carla_msgs::msg::CarlaTrafficLightStatus& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -261,6 +229,8 @@ namespace nav_msgs { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -283,12 +253,12 @@ namespace nav_msgs { eprosima::fastcdr::Cdr& cdr) const; private: + std_msgs::msg::Header m_header; - std::string m_child_frame_id; - geometry_msgs::msg::PoseWithCovariance m_pose; - geometry_msgs::msg::TwistWithCovariance m_twist; + uint32_t m_id; + uint8_t m_state; }; } // namespace msg -} // namespace nav_msgs +} // namespace carla_msgs -#endif // _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRY_H_ +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUS_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusList.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusList.cxx new file mode 100644 index 00000000000..e52f220a571 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusList.cxx @@ -0,0 +1,198 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaTrafficLightStatusList.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaTrafficLightStatusList.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaTrafficLightStatusList::CarlaTrafficLightStatusList() +{ + // m_traffic_lights com.eprosima.idl.parser.typecode.SequenceTypeCode@4be29ed9 + + +} + +carla_msgs::msg::CarlaTrafficLightStatusList::~CarlaTrafficLightStatusList() +{ +} + +carla_msgs::msg::CarlaTrafficLightStatusList::CarlaTrafficLightStatusList( + const CarlaTrafficLightStatusList& x) +{ + m_traffic_lights = x.m_traffic_lights; +} + +carla_msgs::msg::CarlaTrafficLightStatusList::CarlaTrafficLightStatusList( + CarlaTrafficLightStatusList&& x) +{ + m_traffic_lights = std::move(x.m_traffic_lights); +} + +carla_msgs::msg::CarlaTrafficLightStatusList& carla_msgs::msg::CarlaTrafficLightStatusList::operator =( + const CarlaTrafficLightStatusList& x) +{ + + m_traffic_lights = x.m_traffic_lights; + + return *this; +} + +carla_msgs::msg::CarlaTrafficLightStatusList& carla_msgs::msg::CarlaTrafficLightStatusList::operator =( + CarlaTrafficLightStatusList&& x) +{ + + m_traffic_lights = std::move(x.m_traffic_lights); + + return *this; +} + +bool carla_msgs::msg::CarlaTrafficLightStatusList::operator ==( + const CarlaTrafficLightStatusList& x) const +{ + + return (m_traffic_lights == x.m_traffic_lights); +} + +bool carla_msgs::msg::CarlaTrafficLightStatusList::operator !=( + const CarlaTrafficLightStatusList& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaTrafficLightStatusList::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < 100; ++a) + { + current_alignment += carla_msgs::msg::CarlaTrafficLightStatus::getMaxCdrSerializedSize(current_alignment);} + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaTrafficLightStatusList::getCdrSerializedSize( + const carla_msgs::msg::CarlaTrafficLightStatusList& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < data.traffic_lights().size(); ++a) + { + current_alignment += carla_msgs::msg::CarlaTrafficLightStatus::getCdrSerializedSize(data.traffic_lights().at(a), current_alignment);} + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaTrafficLightStatusList::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_traffic_lights; +} + +void carla_msgs::msg::CarlaTrafficLightStatusList::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_traffic_lights;} + +/*! + * @brief This function copies the value in member traffic_lights + * @param _traffic_lights New value to be copied in member traffic_lights + */ +void carla_msgs::msg::CarlaTrafficLightStatusList::traffic_lights( + const std::vector& _traffic_lights) +{ + m_traffic_lights = _traffic_lights; +} + +/*! + * @brief This function moves the value in member traffic_lights + * @param _traffic_lights New value to be moved in member traffic_lights + */ +void carla_msgs::msg::CarlaTrafficLightStatusList::traffic_lights( + std::vector&& _traffic_lights) +{ + m_traffic_lights = std::move(_traffic_lights); +} + +/*! + * @brief This function returns a constant reference to member traffic_lights + * @return Constant reference to member traffic_lights + */ +const std::vector& carla_msgs::msg::CarlaTrafficLightStatusList::traffic_lights() const +{ + return m_traffic_lights; +} + +/*! + * @brief This function returns a reference to member traffic_lights + * @return Reference to member traffic_lights + */ +std::vector& carla_msgs::msg::CarlaTrafficLightStatusList::traffic_lights() +{ + return m_traffic_lights; +} + +size_t carla_msgs::msg::CarlaTrafficLightStatusList::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaTrafficLightStatusList::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaTrafficLightStatusList::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusList.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusList.h new file mode 100644 index 00000000000..31923276573 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusList.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaTrafficLightStatusList.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSLIST_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSLIST_H_ + +#include "CarlaTrafficLightStatus.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CarlaTrafficLightStatusList_SOURCE) +#define CarlaTrafficLightStatusList_DllAPI __declspec( dllexport ) +#else +#define CarlaTrafficLightStatusList_DllAPI __declspec( dllimport ) +#endif // CarlaTrafficLightStatusList_SOURCE +#else +#define CarlaTrafficLightStatusList_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CarlaTrafficLightStatusList_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace msg { + /*! + * @brief This class represents the structure CarlaTrafficLightStatusList defined by the user in the IDL file. + * @ingroup CARLATRAFFICLIGHTSTATUSLIST + */ + class CarlaTrafficLightStatusList + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaTrafficLightStatusList(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaTrafficLightStatusList(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightStatusList that will be copied. + */ + eProsima_user_DllExport CarlaTrafficLightStatusList( + const CarlaTrafficLightStatusList& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightStatusList that will be copied. + */ + eProsima_user_DllExport CarlaTrafficLightStatusList( + CarlaTrafficLightStatusList&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightStatusList that will be copied. + */ + eProsima_user_DllExport CarlaTrafficLightStatusList& operator =( + const CarlaTrafficLightStatusList& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightStatusList that will be copied. + */ + eProsima_user_DllExport CarlaTrafficLightStatusList& operator =( + CarlaTrafficLightStatusList&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaTrafficLightStatusList object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaTrafficLightStatusList& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaTrafficLightStatusList object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaTrafficLightStatusList& x) const; + + /*! + * @brief This function copies the value in member traffic_lights + * @param _traffic_lights New value to be copied in member traffic_lights + */ + eProsima_user_DllExport void traffic_lights( + const std::vector& _traffic_lights); + + /*! + * @brief This function moves the value in member traffic_lights + * @param _traffic_lights New value to be moved in member traffic_lights + */ + eProsima_user_DllExport void traffic_lights( + std::vector&& _traffic_lights); + + /*! + * @brief This function returns a constant reference to member traffic_lights + * @return Constant reference to member traffic_lights + */ + eProsima_user_DllExport const std::vector& traffic_lights() const; + + /*! + * @brief This function returns a reference to member traffic_lights + * @return Reference to member traffic_lights + */ + eProsima_user_DllExport std::vector& traffic_lights(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::msg::CarlaTrafficLightStatusList& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std::vector m_traffic_lights; + }; + } // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSLIST_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusListPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusListPubSubTypes.cxx new file mode 100644 index 00000000000..d31612840d4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusListPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaTrafficLightStatusListPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaTrafficLightStatusListPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaTrafficLightStatusListPubSubType::CarlaTrafficLightStatusListPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaTrafficLightStatusList_"); + auto type_size = CarlaTrafficLightStatusList::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaTrafficLightStatusList::isKeyDefined(); + size_t keyLength = CarlaTrafficLightStatusList::getKeyMaxCdrSerializedSize() > 16 ? + CarlaTrafficLightStatusList::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaTrafficLightStatusListPubSubType::~CarlaTrafficLightStatusListPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaTrafficLightStatusListPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaTrafficLightStatusList* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaTrafficLightStatusListPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaTrafficLightStatusList* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaTrafficLightStatusListPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaTrafficLightStatusListPubSubType::createData() + { + return reinterpret_cast(new CarlaTrafficLightStatusList()); + } + + void CarlaTrafficLightStatusListPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaTrafficLightStatusListPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaTrafficLightStatusList* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaTrafficLightStatusList::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaTrafficLightStatusList::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusListPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusListPubSubTypes.h new file mode 100644 index 00000000000..185f5c53918 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusListPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaTrafficLightStatusListPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSLIST_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSLIST_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaTrafficLightStatusList.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaTrafficLightStatusList is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CarlaTrafficLightStatusList defined by the user in the IDL file. + * @ingroup CARLATRAFFICLIGHTSTATUSLIST + */ + class CarlaTrafficLightStatusListPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaTrafficLightStatusList type; + + eProsima_user_DllExport CarlaTrafficLightStatusListPubSubType(); + + eProsima_user_DllExport virtual ~CarlaTrafficLightStatusListPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSLIST_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusPubSubTypes.cxx new file mode 100644 index 00000000000..1f461e58653 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusPubSubTypes.cxx @@ -0,0 +1,184 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaTrafficLightStatusPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaTrafficLightStatusPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + namespace CarlaTrafficLightStatus_Constants { + + + + + + + } //End of namespace CarlaTrafficLightStatus_Constants + CarlaTrafficLightStatusPubSubType::CarlaTrafficLightStatusPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaTrafficLightStatus_"); + auto type_size = CarlaTrafficLightStatus::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaTrafficLightStatus::isKeyDefined(); + size_t keyLength = CarlaTrafficLightStatus::getKeyMaxCdrSerializedSize() > 16 ? + CarlaTrafficLightStatus::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaTrafficLightStatusPubSubType::~CarlaTrafficLightStatusPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaTrafficLightStatusPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaTrafficLightStatus* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaTrafficLightStatusPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaTrafficLightStatus* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaTrafficLightStatusPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaTrafficLightStatusPubSubType::createData() + { + return reinterpret_cast(new CarlaTrafficLightStatus()); + } + + void CarlaTrafficLightStatusPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaTrafficLightStatusPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaTrafficLightStatus* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaTrafficLightStatus::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaTrafficLightStatus::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusPubSubTypes.h new file mode 100644 index 00000000000..b842189b98a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusPubSubTypes.h @@ -0,0 +1,115 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaTrafficLightStatusPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUS_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaTrafficLightStatus.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaTrafficLightStatus is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + namespace CarlaTrafficLightStatus_Constants + { + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type CarlaTrafficLightStatus defined by the user in the IDL file. + * @ingroup CARLATRAFFICLIGHTSTATUS + */ + class CarlaTrafficLightStatusPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaTrafficLightStatus type; + + eProsima_user_DllExport CarlaTrafficLightStatusPubSubType(); + + eProsima_user_DllExport virtual ~CarlaTrafficLightStatusPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUS_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArray.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArray.cxx new file mode 100644 index 00000000000..1c310bd2a7d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArray.cxx @@ -0,0 +1,242 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XByteArray.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaV2XByteArray.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +carla_msgs::msg::CarlaV2XByteArray::CarlaV2XByteArray() +{ + // m_data_size com.eprosima.idl.parser.typecode.PrimitiveTypeCode@1a75e76a + m_data_size = 0; + // m_bytes com.eprosima.idl.parser.typecode.AliasTypeCode@5524cca1 + memset(&m_bytes, 0, (100) * 1); + +} + +carla_msgs::msg::CarlaV2XByteArray::~CarlaV2XByteArray() +{ + +} + +carla_msgs::msg::CarlaV2XByteArray::CarlaV2XByteArray( + const CarlaV2XByteArray& x) +{ + m_data_size = x.m_data_size; + m_bytes = x.m_bytes; +} + +carla_msgs::msg::CarlaV2XByteArray::CarlaV2XByteArray( + CarlaV2XByteArray&& x) +{ + m_data_size = x.m_data_size; + m_bytes = std::move(x.m_bytes); +} + +carla_msgs::msg::CarlaV2XByteArray& carla_msgs::msg::CarlaV2XByteArray::operator =( + const CarlaV2XByteArray& x) +{ + + m_data_size = x.m_data_size; + m_bytes = x.m_bytes; + + return *this; +} + +carla_msgs::msg::CarlaV2XByteArray& carla_msgs::msg::CarlaV2XByteArray::operator =( + CarlaV2XByteArray&& x) +{ + + m_data_size = x.m_data_size; + m_bytes = std::move(x.m_bytes); + + return *this; +} + +bool carla_msgs::msg::CarlaV2XByteArray::operator ==( + const CarlaV2XByteArray& x) const +{ + + return (m_data_size == x.m_data_size && m_bytes == x.m_bytes); +} + +bool carla_msgs::msg::CarlaV2XByteArray::operator !=( + const CarlaV2XByteArray& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaV2XByteArray::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += ((100) * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaV2XByteArray::getCdrSerializedSize( + const carla_msgs::msg::CarlaV2XByteArray& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + if ((100) > 0) + { + current_alignment += ((100) * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + } + + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaV2XByteArray::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_data_size; + scdr << m_bytes; + + +} + +void carla_msgs::msg::CarlaV2XByteArray::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_data_size; + dcdr >> m_bytes; + +} + +/*! + * @brief This function sets a value in member data_size + * @param _data_size New value for member data_size + */ +void carla_msgs::msg::CarlaV2XByteArray::data_size( + uint8_t _data_size) +{ + m_data_size = _data_size; +} + +/*! + * @brief This function returns the value of member data_size + * @return Value of member data_size + */ +uint8_t carla_msgs::msg::CarlaV2XByteArray::data_size() const +{ + return m_data_size; +} + +/*! + * @brief This function returns a reference to member data_size + * @return Reference to member data_size + */ +uint8_t& carla_msgs::msg::CarlaV2XByteArray::data_size() +{ + return m_data_size; +} + +/*! + * @brief This function copies the value in member bytes + * @param _bytes New value to be copied in member bytes + */ +void carla_msgs::msg::CarlaV2XByteArray::bytes( + const carla_msgs::msg::octet__100& _bytes) +{ + m_bytes = _bytes; +} + +/*! + * @brief This function moves the value in member bytes + * @param _bytes New value to be moved in member bytes + */ +void carla_msgs::msg::CarlaV2XByteArray::bytes( + carla_msgs::msg::octet__100&& _bytes) +{ + m_bytes = std::move(_bytes); +} + +/*! + * @brief This function returns a constant reference to member bytes + * @return Constant reference to member bytes + */ +const carla_msgs::msg::octet__100& carla_msgs::msg::CarlaV2XByteArray::bytes() const +{ + return m_bytes; +} + +/*! + * @brief This function returns a reference to member bytes + * @return Reference to member bytes + */ +carla_msgs::msg::octet__100& carla_msgs::msg::CarlaV2XByteArray::bytes() +{ + return m_bytes; +} + +size_t carla_msgs::msg::CarlaV2XByteArray::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaV2XByteArray::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaV2XByteArray::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/types/TF2Error.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArray.h similarity index 55% rename from LibCarla/source/carla/ros2/types/TF2Error.h rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArray.h index 07b5804d4db..2e7ff27a1af 100644 --- a/LibCarla/source/carla/ros2/types/TF2Error.h +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArray.h @@ -13,16 +13,15 @@ // limitations under the License. /*! - * @file TF2Error.h + * @file CarlaV2XByteArray.h * This header file contains the declaration of the described types in the IDL file. * * This file was generated by the tool gen. */ -#ifndef _FAST_DDS_GENERATED_TF2_MSGS_MSG_TF2ERROR_H_ -#define _FAST_DDS_GENERATED_TF2_MSGS_MSG_TF2ERROR_H_ +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XBYTEARRAY_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XBYTEARRAY_H_ -#include #include #include @@ -43,16 +42,16 @@ #if defined(_WIN32) #if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(TF2Error_SOURCE) -#define TF2Error_DllAPI __declspec( dllexport ) +#if defined(CarlaV2XByteArray_SOURCE) +#define CarlaV2XByteArray_DllAPI __declspec( dllexport ) #else -#define TF2Error_DllAPI __declspec( dllimport ) -#endif // TF2Error_SOURCE +#define CarlaV2XByteArray_DllAPI __declspec( dllimport ) +#endif // CarlaV2XByteArray_SOURCE #else -#define TF2Error_DllAPI +#define CarlaV2XByteArray_DllAPI #endif // EPROSIMA_USER_DLL_EXPORT #else -#define TF2Error_DllAPI +#define CarlaV2XByteArray_DllAPI #endif // _WIN32 namespace eprosima { @@ -62,126 +61,120 @@ class Cdr; } // namespace eprosima -namespace tf2_msgs { +namespace carla_msgs { namespace msg { - const uint8_t TF2Error__NO_ERROR = 0; - const uint8_t TF2Error__LOOKUP_ERROR = 1; - const uint8_t TF2Error__CONNECTIVITY_ERROR = 2; - const uint8_t TF2Error__EXTRAPOLATION_ERROR = 3; - const uint8_t TF2Error__INVALID_ARGUMENT_ERROR = 4; - const uint8_t TF2Error__TIMEOUT_ERROR = 5; - const uint8_t TF2Error__TRANSFORM_ERROR = 6; + typedef std::array octet__100; /*! - * @brief This class represents the structure TF2Error defined by the user in the IDL file. - * @ingroup TF2ERROR + * @brief This class represents the structure CarlaV2XByteArray defined by the user in the IDL file. + * @ingroup CARLAV2XBYTEARRAY */ - class TF2Error + class CarlaV2XByteArray { public: /*! * @brief Default constructor. */ - eProsima_user_DllExport TF2Error(); + eProsima_user_DllExport CarlaV2XByteArray(); /*! * @brief Default destructor. */ - eProsima_user_DllExport ~TF2Error(); + eProsima_user_DllExport ~CarlaV2XByteArray(); /*! * @brief Copy constructor. - * @param x Reference to the object tf2_msgs::msg::TF2Error that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaV2XByteArray that will be copied. */ - eProsima_user_DllExport TF2Error( - const TF2Error& x); + eProsima_user_DllExport CarlaV2XByteArray( + const CarlaV2XByteArray& x); /*! * @brief Move constructor. - * @param x Reference to the object tf2_msgs::msg::TF2Error that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaV2XByteArray that will be copied. */ - eProsima_user_DllExport TF2Error( - TF2Error&& x) noexcept; + eProsima_user_DllExport CarlaV2XByteArray( + CarlaV2XByteArray&& x); /*! * @brief Copy assignment. - * @param x Reference to the object tf2_msgs::msg::TF2Error that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaV2XByteArray that will be copied. */ - eProsima_user_DllExport TF2Error& operator =( - const TF2Error& x); + eProsima_user_DllExport CarlaV2XByteArray& operator =( + const CarlaV2XByteArray& x); /*! * @brief Move assignment. - * @param x Reference to the object tf2_msgs::msg::TF2Error that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaV2XByteArray that will be copied. */ - eProsima_user_DllExport TF2Error& operator =( - TF2Error&& x) noexcept; + eProsima_user_DllExport CarlaV2XByteArray& operator =( + CarlaV2XByteArray&& x); /*! * @brief Comparison operator. - * @param x tf2_msgs::msg::TF2Error object to compare. + * @param x carla_msgs::msg::CarlaV2XByteArray object to compare. */ eProsima_user_DllExport bool operator ==( - const TF2Error& x) const; + const CarlaV2XByteArray& x) const; /*! * @brief Comparison operator. - * @param x tf2_msgs::msg::TF2Error object to compare. + * @param x carla_msgs::msg::CarlaV2XByteArray object to compare. */ eProsima_user_DllExport bool operator !=( - const TF2Error& x) const; + const CarlaV2XByteArray& x) const; /*! - * @brief This function sets a value in member error - * @param _error New value for member error + * @brief This function sets a value in member data_size + * @param _data_size New value for member data_size */ - eProsima_user_DllExport void error( - uint8_t _error); + eProsima_user_DllExport void data_size( + uint8_t _data_size); /*! - * @brief This function returns the value of member error - * @return Value of member error + * @brief This function returns the value of member data_size + * @return Value of member data_size */ - eProsima_user_DllExport uint8_t error() const; + eProsima_user_DllExport uint8_t data_size() const; /*! - * @brief This function returns a reference to member error - * @return Reference to member error + * @brief This function returns a reference to member data_size + * @return Reference to member data_size */ - eProsima_user_DllExport uint8_t& error(); + eProsima_user_DllExport uint8_t& data_size(); /*! - * @brief This function copies the value in member error_string - * @param _error_string New value to be copied in member error_string + * @brief This function copies the value in member bytes + * @param _bytes New value to be copied in member bytes */ - eProsima_user_DllExport void error_string( - const std::string& _error_string); + eProsima_user_DllExport void bytes( + const carla_msgs::msg::octet__100& _bytes); /*! - * @brief This function moves the value in member error_string - * @param _error_string New value to be moved in member error_string + * @brief This function moves the value in member bytes + * @param _bytes New value to be moved in member bytes */ - eProsima_user_DllExport void error_string( - std::string&& _error_string); + eProsima_user_DllExport void bytes( + carla_msgs::msg::octet__100&& _bytes); /*! - * @brief This function returns a constant reference to member error_string - * @return Constant reference to member error_string + * @brief This function returns a constant reference to member bytes + * @return Constant reference to member bytes */ - eProsima_user_DllExport const std::string& error_string() const; + eProsima_user_DllExport const carla_msgs::msg::octet__100& bytes() const; /*! - * @brief This function returns a reference to member error_string - * @return Reference to member error_string + * @brief This function returns a reference to member bytes + * @return Reference to member bytes */ - eProsima_user_DllExport std::string& error_string(); + eProsima_user_DllExport carla_msgs::msg::octet__100& bytes(); /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -192,9 +185,10 @@ namespace tf2_msgs { * @return Serialized size. */ eProsima_user_DllExport static size_t getCdrSerializedSize( - const tf2_msgs::msg::TF2Error& data, + const carla_msgs::msg::CarlaV2XByteArray& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -209,6 +203,8 @@ namespace tf2_msgs { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -231,10 +227,11 @@ namespace tf2_msgs { eprosima::fastcdr::Cdr& cdr) const; private: - uint8_t m_error; - std::string m_error_string; + + uint8_t m_data_size; + carla_msgs::msg::octet__100 m_bytes; }; } // namespace msg -} // namespace tf2_msgs +} // namespace carla_msgs -#endif // _FAST_DDS_GENERATED_TF2_MSGS_MSG_TF2ERROR_H_ +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XBYTEARRAY_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArrayPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArrayPubSubTypes.cxx new file mode 100644 index 00000000000..7780afaa68f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArrayPubSubTypes.cxx @@ -0,0 +1,177 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XByteArrayPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaV2XByteArrayPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + + CarlaV2XByteArrayPubSubType::CarlaV2XByteArrayPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaV2XByteArray_"); + auto type_size = CarlaV2XByteArray::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaV2XByteArray::isKeyDefined(); + size_t keyLength = CarlaV2XByteArray::getKeyMaxCdrSerializedSize() > 16 ? + CarlaV2XByteArray::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaV2XByteArrayPubSubType::~CarlaV2XByteArrayPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaV2XByteArrayPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaV2XByteArray* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaV2XByteArrayPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaV2XByteArray* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaV2XByteArrayPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaV2XByteArrayPubSubType::createData() + { + return reinterpret_cast(new CarlaV2XByteArray()); + } + + void CarlaV2XByteArrayPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaV2XByteArrayPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaV2XByteArray* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaV2XByteArray::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaV2XByteArray::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArrayPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArrayPubSubTypes.h new file mode 100644 index 00000000000..e8fa6fafc18 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArrayPubSubTypes.h @@ -0,0 +1,108 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XByteArrayPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XBYTEARRAY_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XBYTEARRAY_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaV2XByteArray.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaV2XByteArray is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + typedef std::array octet__100; + /*! + * @brief This class represents the TopicDataType of the type CarlaV2XByteArray defined by the user in the IDL file. + * @ingroup CARLAV2XBYTEARRAY + */ + class CarlaV2XByteArrayPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaV2XByteArray type; + + eProsima_user_DllExport CarlaV2XByteArrayPubSubType(); + + eProsima_user_DllExport virtual ~CarlaV2XByteArrayPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) CarlaV2XByteArray(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XBYTEARRAY_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustom.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustom.cxx new file mode 100644 index 00000000000..5d9c94909e1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustom.cxx @@ -0,0 +1,240 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XCustom.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaV2XCustom.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaV2XCustom::CarlaV2XCustom() +{ + // m_header com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@5fdcaa40 + + // m_message com.eprosima.idl.parser.typecode.StringTypeCode@6dc17b83 + m_message =""; + +} + +carla_msgs::msg::CarlaV2XCustom::~CarlaV2XCustom() +{ + +} + +carla_msgs::msg::CarlaV2XCustom::CarlaV2XCustom( + const CarlaV2XCustom& x) +{ + m_header = x.m_header; + m_message = x.m_message; +} + +carla_msgs::msg::CarlaV2XCustom::CarlaV2XCustom( + CarlaV2XCustom&& x) +{ + m_header = std::move(x.m_header); + m_message = std::move(x.m_message); +} + +carla_msgs::msg::CarlaV2XCustom& carla_msgs::msg::CarlaV2XCustom::operator =( + const CarlaV2XCustom& x) +{ + + m_header = x.m_header; + m_message = x.m_message; + + return *this; +} + +carla_msgs::msg::CarlaV2XCustom& carla_msgs::msg::CarlaV2XCustom::operator =( + CarlaV2XCustom&& x) +{ + + m_header = std::move(x.m_header); + m_message = std::move(x.m_message); + + return *this; +} + +bool carla_msgs::msg::CarlaV2XCustom::operator ==( + const CarlaV2XCustom& x) const +{ + + return (m_header == x.m_header && m_message == x.m_message); +} + +bool carla_msgs::msg::CarlaV2XCustom::operator !=( + const CarlaV2XCustom& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaV2XCustom::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::ItsPduHeader::getMaxCdrSerializedSize(current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaV2XCustom::getCdrSerializedSize( + const carla_msgs::msg::CarlaV2XCustom& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::ItsPduHeader::getCdrSerializedSize(data.header(), current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.message().size() + 1; + + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaV2XCustom::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_header; + scdr << m_message; + +} + +void carla_msgs::msg::CarlaV2XCustom::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_header; + dcdr >> m_message; +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void carla_msgs::msg::CarlaV2XCustom::header( + const etsi_its_cam_msgs::msg::ItsPduHeader& _header) +{ + m_header = _header; +} + +/*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ +void carla_msgs::msg::CarlaV2XCustom::header( + etsi_its_cam_msgs::msg::ItsPduHeader&& _header) +{ + m_header = std::move(_header); +} + +/*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ +const etsi_its_cam_msgs::msg::ItsPduHeader& carla_msgs::msg::CarlaV2XCustom::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +etsi_its_cam_msgs::msg::ItsPduHeader& carla_msgs::msg::CarlaV2XCustom::header() +{ + return m_header; +} +/*! + * @brief This function copies the value in member message + * @param _message New value to be copied in member message + */ +void carla_msgs::msg::CarlaV2XCustom::message( + const std::string& _message) +{ + m_message = _message; +} + +/*! + * @brief This function moves the value in member message + * @param _message New value to be moved in member message + */ +void carla_msgs::msg::CarlaV2XCustom::message( + std::string&& _message) +{ + m_message = std::move(_message); +} + +/*! + * @brief This function returns a constant reference to member message + * @return Constant reference to member message + */ +const std::string& carla_msgs::msg::CarlaV2XCustom::message() const +{ + return m_message; +} + +/*! + * @brief This function returns a reference to member message + * @return Reference to member message + */ +std::string& carla_msgs::msg::CarlaV2XCustom::message() +{ + return m_message; +} + +size_t carla_msgs::msg::CarlaV2XCustom::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaV2XCustom::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaV2XCustom::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustom.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustom.h new file mode 100644 index 00000000000..e07b55ef863 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustom.h @@ -0,0 +1,243 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XCustom.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOM_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOM_H_ + +#include "etsi_its_cam_msgs/msg/ItsPduHeader.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CarlaV2XCustom_SOURCE) +#define CarlaV2XCustom_DllAPI __declspec( dllexport ) +#else +#define CarlaV2XCustom_DllAPI __declspec( dllimport ) +#endif // CarlaV2XCustom_SOURCE +#else +#define CarlaV2XCustom_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CarlaV2XCustom_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace msg { + /*! + * @brief This class represents the structure CarlaV2XCustom defined by the user in the IDL file. + * @ingroup CARLAV2XCUSTOM + */ + class CarlaV2XCustom + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaV2XCustom(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaV2XCustom(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaV2XCustom that will be copied. + */ + eProsima_user_DllExport CarlaV2XCustom( + const CarlaV2XCustom& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaV2XCustom that will be copied. + */ + eProsima_user_DllExport CarlaV2XCustom( + CarlaV2XCustom&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaV2XCustom that will be copied. + */ + eProsima_user_DllExport CarlaV2XCustom& operator =( + const CarlaV2XCustom& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaV2XCustom that will be copied. + */ + eProsima_user_DllExport CarlaV2XCustom& operator =( + CarlaV2XCustom&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaV2XCustom object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaV2XCustom& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaV2XCustom object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaV2XCustom& x) const; + + /*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ + eProsima_user_DllExport void header( + const etsi_its_cam_msgs::msg::ItsPduHeader& _header); + + /*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ + eProsima_user_DllExport void header( + etsi_its_cam_msgs::msg::ItsPduHeader&& _header); + + /*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::ItsPduHeader& header() const; + + /*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::ItsPduHeader& header(); + /*! + * @brief This function copies the value in member message + * @param _message New value to be copied in member message + */ + eProsima_user_DllExport void message( + const std::string& _message); + + /*! + * @brief This function moves the value in member message + * @param _message New value to be moved in member message + */ + eProsima_user_DllExport void message( + std::string&& _message); + + /*! + * @brief This function returns a constant reference to member message + * @return Constant reference to member message + */ + eProsima_user_DllExport const std::string& message() const; + + /*! + * @brief This function returns a reference to member message + * @return Reference to member message + */ + eProsima_user_DllExport std::string& message(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::msg::CarlaV2XCustom& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::ItsPduHeader m_header; + std::string m_message; + }; + } // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOM_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomData.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomData.cxx new file mode 100644 index 00000000000..9c2e642ea8e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomData.cxx @@ -0,0 +1,233 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XCustomData.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaV2XCustomData.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaV2XCustomData::CarlaV2XCustomData() +{ + // m_power com.eprosima.idl.parser.typecode.PrimitiveTypeCode@6be968ce + m_power = 0.0; + // m_message com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@7c37508a + + +} + +carla_msgs::msg::CarlaV2XCustomData::~CarlaV2XCustomData() +{ + +} + +carla_msgs::msg::CarlaV2XCustomData::CarlaV2XCustomData( + const CarlaV2XCustomData& x) +{ + m_power = x.m_power; + m_message = x.m_message; +} + +carla_msgs::msg::CarlaV2XCustomData::CarlaV2XCustomData( + CarlaV2XCustomData&& x) +{ + m_power = x.m_power; + m_message = std::move(x.m_message); +} + +carla_msgs::msg::CarlaV2XCustomData& carla_msgs::msg::CarlaV2XCustomData::operator =( + const CarlaV2XCustomData& x) +{ + + m_power = x.m_power; + m_message = x.m_message; + + return *this; +} + +carla_msgs::msg::CarlaV2XCustomData& carla_msgs::msg::CarlaV2XCustomData::operator =( + CarlaV2XCustomData&& x) +{ + + m_power = x.m_power; + m_message = std::move(x.m_message); + + return *this; +} + +bool carla_msgs::msg::CarlaV2XCustomData::operator ==( + const CarlaV2XCustomData& x) const +{ + + return (m_power == x.m_power && m_message == x.m_message); +} + +bool carla_msgs::msg::CarlaV2XCustomData::operator !=( + const CarlaV2XCustomData& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaV2XCustomData::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += carla_msgs::msg::CarlaV2XCustomMessage::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaV2XCustomData::getCdrSerializedSize( + const carla_msgs::msg::CarlaV2XCustomData& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += carla_msgs::msg::CarlaV2XCustomMessage::getCdrSerializedSize(data.message(), current_alignment); + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaV2XCustomData::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_power; + scdr << m_message; + +} + +void carla_msgs::msg::CarlaV2XCustomData::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_power; + dcdr >> m_message; +} + +/*! + * @brief This function sets a value in member power + * @param _power New value for member power + */ +void carla_msgs::msg::CarlaV2XCustomData::power( + float _power) +{ + m_power = _power; +} + +/*! + * @brief This function returns the value of member power + * @return Value of member power + */ +float carla_msgs::msg::CarlaV2XCustomData::power() const +{ + return m_power; +} + +/*! + * @brief This function returns a reference to member power + * @return Reference to member power + */ +float& carla_msgs::msg::CarlaV2XCustomData::power() +{ + return m_power; +} + +/*! + * @brief This function copies the value in member message + * @param _message New value to be copied in member message + */ +void carla_msgs::msg::CarlaV2XCustomData::message( + const carla_msgs::msg::CarlaV2XCustomMessage& _message) +{ + m_message = _message; +} + +/*! + * @brief This function moves the value in member message + * @param _message New value to be moved in member message + */ +void carla_msgs::msg::CarlaV2XCustomData::message( + carla_msgs::msg::CarlaV2XCustomMessage&& _message) +{ + m_message = std::move(_message); +} + +/*! + * @brief This function returns a constant reference to member message + * @return Constant reference to member message + */ +const carla_msgs::msg::CarlaV2XCustomMessage& carla_msgs::msg::CarlaV2XCustomData::message() const +{ + return m_message; +} + +/*! + * @brief This function returns a reference to member message + * @return Reference to member message + */ +carla_msgs::msg::CarlaV2XCustomMessage& carla_msgs::msg::CarlaV2XCustomData::message() +{ + return m_message; +} + +size_t carla_msgs::msg::CarlaV2XCustomData::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaV2XCustomData::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaV2XCustomData::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomData.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomData.h new file mode 100644 index 00000000000..c41a1ece1d0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomData.h @@ -0,0 +1,237 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XCustomData.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATA_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATA_H_ + +#include "CarlaV2XCustomMessage.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CarlaV2XCustomData_SOURCE) +#define CarlaV2XCustomData_DllAPI __declspec( dllexport ) +#else +#define CarlaV2XCustomData_DllAPI __declspec( dllimport ) +#endif // CarlaV2XCustomData_SOURCE +#else +#define CarlaV2XCustomData_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CarlaV2XCustomData_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace msg { + /*! + * @brief This class represents the structure CarlaV2XCustomData defined by the user in the IDL file. + * @ingroup CARLAV2XCUSTOMDATA + */ + class CarlaV2XCustomData + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaV2XCustomData(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaV2XCustomData(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaV2XCustomData that will be copied. + */ + eProsima_user_DllExport CarlaV2XCustomData( + const CarlaV2XCustomData& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaV2XCustomData that will be copied. + */ + eProsima_user_DllExport CarlaV2XCustomData( + CarlaV2XCustomData&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaV2XCustomData that will be copied. + */ + eProsima_user_DllExport CarlaV2XCustomData& operator =( + const CarlaV2XCustomData& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaV2XCustomData that will be copied. + */ + eProsima_user_DllExport CarlaV2XCustomData& operator =( + CarlaV2XCustomData&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaV2XCustomData object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaV2XCustomData& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaV2XCustomData object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaV2XCustomData& x) const; + + /*! + * @brief This function sets a value in member power + * @param _power New value for member power + */ + eProsima_user_DllExport void power( + float _power); + + /*! + * @brief This function returns the value of member power + * @return Value of member power + */ + eProsima_user_DllExport float power() const; + + /*! + * @brief This function returns a reference to member power + * @return Reference to member power + */ + eProsima_user_DllExport float& power(); + + /*! + * @brief This function copies the value in member message + * @param _message New value to be copied in member message + */ + eProsima_user_DllExport void message( + const carla_msgs::msg::CarlaV2XCustomMessage& _message); + + /*! + * @brief This function moves the value in member message + * @param _message New value to be moved in member message + */ + eProsima_user_DllExport void message( + carla_msgs::msg::CarlaV2XCustomMessage&& _message); + + /*! + * @brief This function returns a constant reference to member message + * @return Constant reference to member message + */ + eProsima_user_DllExport const carla_msgs::msg::CarlaV2XCustomMessage& message() const; + + /*! + * @brief This function returns a reference to member message + * @return Reference to member message + */ + eProsima_user_DllExport carla_msgs::msg::CarlaV2XCustomMessage& message(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::msg::CarlaV2XCustomData& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + float m_power; + carla_msgs::msg::CarlaV2XCustomMessage m_message; + }; + } // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATA_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataList.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataList.cxx new file mode 100644 index 00000000000..d55fe266e57 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataList.cxx @@ -0,0 +1,198 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XCustomDataList.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaV2XCustomDataList.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaV2XCustomDataList::CarlaV2XCustomDataList() +{ + // m_data com.eprosima.idl.parser.typecode.SequenceTypeCode@723ca036 + + +} + +carla_msgs::msg::CarlaV2XCustomDataList::~CarlaV2XCustomDataList() +{ +} + +carla_msgs::msg::CarlaV2XCustomDataList::CarlaV2XCustomDataList( + const CarlaV2XCustomDataList& x) +{ + m_data = x.m_data; +} + +carla_msgs::msg::CarlaV2XCustomDataList::CarlaV2XCustomDataList( + CarlaV2XCustomDataList&& x) +{ + m_data = std::move(x.m_data); +} + +carla_msgs::msg::CarlaV2XCustomDataList& carla_msgs::msg::CarlaV2XCustomDataList::operator =( + const CarlaV2XCustomDataList& x) +{ + + m_data = x.m_data; + + return *this; +} + +carla_msgs::msg::CarlaV2XCustomDataList& carla_msgs::msg::CarlaV2XCustomDataList::operator =( + CarlaV2XCustomDataList&& x) +{ + + m_data = std::move(x.m_data); + + return *this; +} + +bool carla_msgs::msg::CarlaV2XCustomDataList::operator ==( + const CarlaV2XCustomDataList& x) const +{ + + return (m_data == x.m_data); +} + +bool carla_msgs::msg::CarlaV2XCustomDataList::operator !=( + const CarlaV2XCustomDataList& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaV2XCustomDataList::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < 100; ++a) + { + current_alignment += carla_msgs::msg::CarlaV2XCustomData::getMaxCdrSerializedSize(current_alignment);} + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaV2XCustomDataList::getCdrSerializedSize( + const carla_msgs::msg::CarlaV2XCustomDataList& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < data.data().size(); ++a) + { + current_alignment += carla_msgs::msg::CarlaV2XCustomData::getCdrSerializedSize(data.data().at(a), current_alignment);} + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaV2XCustomDataList::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_data; +} + +void carla_msgs::msg::CarlaV2XCustomDataList::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_data;} + +/*! + * @brief This function copies the value in member data + * @param _data New value to be copied in member data + */ +void carla_msgs::msg::CarlaV2XCustomDataList::data( + const std::vector& _data) +{ + m_data = _data; +} + +/*! + * @brief This function moves the value in member data + * @param _data New value to be moved in member data + */ +void carla_msgs::msg::CarlaV2XCustomDataList::data( + std::vector&& _data) +{ + m_data = std::move(_data); +} + +/*! + * @brief This function returns a constant reference to member data + * @return Constant reference to member data + */ +const std::vector& carla_msgs::msg::CarlaV2XCustomDataList::data() const +{ + return m_data; +} + +/*! + * @brief This function returns a reference to member data + * @return Reference to member data + */ +std::vector& carla_msgs::msg::CarlaV2XCustomDataList::data() +{ + return m_data; +} + +size_t carla_msgs::msg::CarlaV2XCustomDataList::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaV2XCustomDataList::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaV2XCustomDataList::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataList.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataList.h new file mode 100644 index 00000000000..7a3e80a10fe --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataList.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XCustomDataList.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATALIST_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATALIST_H_ + +#include "CarlaV2XCustomData.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CarlaV2XCustomDataList_SOURCE) +#define CarlaV2XCustomDataList_DllAPI __declspec( dllexport ) +#else +#define CarlaV2XCustomDataList_DllAPI __declspec( dllimport ) +#endif // CarlaV2XCustomDataList_SOURCE +#else +#define CarlaV2XCustomDataList_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CarlaV2XCustomDataList_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace msg { + /*! + * @brief This class represents the structure CarlaV2XCustomDataList defined by the user in the IDL file. + * @ingroup CARLAV2XCUSTOMDATALIST + */ + class CarlaV2XCustomDataList + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaV2XCustomDataList(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaV2XCustomDataList(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaV2XCustomDataList that will be copied. + */ + eProsima_user_DllExport CarlaV2XCustomDataList( + const CarlaV2XCustomDataList& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaV2XCustomDataList that will be copied. + */ + eProsima_user_DllExport CarlaV2XCustomDataList( + CarlaV2XCustomDataList&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaV2XCustomDataList that will be copied. + */ + eProsima_user_DllExport CarlaV2XCustomDataList& operator =( + const CarlaV2XCustomDataList& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaV2XCustomDataList that will be copied. + */ + eProsima_user_DllExport CarlaV2XCustomDataList& operator =( + CarlaV2XCustomDataList&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaV2XCustomDataList object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaV2XCustomDataList& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaV2XCustomDataList object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaV2XCustomDataList& x) const; + + /*! + * @brief This function copies the value in member data + * @param _data New value to be copied in member data + */ + eProsima_user_DllExport void data( + const std::vector& _data); + + /*! + * @brief This function moves the value in member data + * @param _data New value to be moved in member data + */ + eProsima_user_DllExport void data( + std::vector&& _data); + + /*! + * @brief This function returns a constant reference to member data + * @return Constant reference to member data + */ + eProsima_user_DllExport const std::vector& data() const; + + /*! + * @brief This function returns a reference to member data + * @return Reference to member data + */ + eProsima_user_DllExport std::vector& data(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::msg::CarlaV2XCustomDataList& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std::vector m_data; + }; + } // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATALIST_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/CarlaEgoVehicleControlPubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataListPubSubTypes.cxx similarity index 67% rename from LibCarla/source/carla/ros2/types/CarlaEgoVehicleControlPubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataListPubSubTypes.cxx index c5ff5216967..c2886fe3a52 100644 --- a/LibCarla/source/carla/ros2/types/CarlaEgoVehicleControlPubSubTypes.cpp +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataListPubSubTypes.cxx @@ -13,36 +13,37 @@ // limitations under the License. /*! - * @file CarlaEgoCarlaEgoVehicleControlPubSubTypes.cpp + * @file CarlaV2XCustomDataListPubSubTypes.cpp * This header file contains the implementation of the serialization functions. * * This file was generated by the tool fastcdrgen. */ + #include #include -#include "CarlaEgoVehicleControlPubSubTypes.h" +#include "CarlaV2XCustomDataListPubSubTypes.h" using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; namespace carla_msgs { namespace msg { - CarlaEgoVehicleControlPubSubType::CarlaEgoVehicleControlPubSubType() + CarlaV2XCustomDataListPubSubType::CarlaV2XCustomDataListPubSubType() { - setName("carla_msgs::msg::dds_::CarlaEgoVehicleControl_"); - auto type_size = CarlaEgoVehicleControl::getMaxCdrSerializedSize(); + setName("carla_msgs::msg::dds_::CarlaV2XCustomDataList_"); + auto type_size = CarlaV2XCustomDataList::getMaxCdrSerializedSize(); type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = CarlaEgoVehicleControl::isKeyDefined(); - size_t keyLength = CarlaEgoVehicleControl::getKeyMaxCdrSerializedSize() > 16 ? - CarlaEgoVehicleControl::getKeyMaxCdrSerializedSize() : 16; + m_isGetKeyDefined = CarlaV2XCustomDataList::isKeyDefined(); + size_t keyLength = CarlaV2XCustomDataList::getKeyMaxCdrSerializedSize() > 16 ? + CarlaV2XCustomDataList::getKeyMaxCdrSerializedSize() : 16; m_keyBuffer = reinterpret_cast(malloc(keyLength)); memset(m_keyBuffer, 0, keyLength); } - CarlaEgoVehicleControlPubSubType::~CarlaEgoVehicleControlPubSubType() + CarlaV2XCustomDataListPubSubType::~CarlaV2XCustomDataListPubSubType() { if (m_keyBuffer != nullptr) { @@ -50,11 +51,11 @@ namespace carla_msgs { } } - bool CarlaEgoVehicleControlPubSubType::serialize( + bool CarlaV2XCustomDataListPubSubType::serialize( void* data, SerializedPayload_t* payload) { - CarlaEgoVehicleControl* p_type = static_cast(data); + CarlaV2XCustomDataList* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); @@ -79,25 +80,25 @@ namespace carla_msgs { return true; } - bool CarlaEgoVehicleControlPubSubType::deserialize( + bool CarlaV2XCustomDataListPubSubType::deserialize( SerializedPayload_t* payload, void* data) { - try - { - //Convert DATA to pointer of your type - CarlaEgoVehicleControl* p_type = static_cast(data); + //Convert DATA to pointer of your type + CarlaV2XCustomDataList* p_type = static_cast(data); - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); - // Deserialize encapsulation. - deser.read_encapsulation(); - payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + try + { // Deserialize the object. p_type->deserialize(deser); } @@ -109,28 +110,28 @@ namespace carla_msgs { return true; } - std::function CarlaEgoVehicleControlPubSubType::getSerializedSizeProvider( + std::function CarlaV2XCustomDataListPubSubType::getSerializedSizeProvider( void* data) { return [data]() -> uint32_t { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + 4u /*encapsulation*/; }; } - void* CarlaEgoVehicleControlPubSubType::createData() + void* CarlaV2XCustomDataListPubSubType::createData() { - return reinterpret_cast(new CarlaEgoVehicleControl()); + return reinterpret_cast(new CarlaV2XCustomDataList()); } - void CarlaEgoVehicleControlPubSubType::deleteData( + void CarlaV2XCustomDataListPubSubType::deleteData( void* data) { - delete(reinterpret_cast(data)); + delete(reinterpret_cast(data)); } - bool CarlaEgoVehicleControlPubSubType::getKey( + bool CarlaV2XCustomDataListPubSubType::getKey( void* data, InstanceHandle_t* handle, bool force_md5) @@ -140,16 +141,16 @@ namespace carla_msgs { return false; } - CarlaEgoVehicleControl* p_type = static_cast(data); + CarlaV2XCustomDataList* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - CarlaEgoVehicleControl::getKeyMaxCdrSerializedSize()); + CarlaV2XCustomDataList::getKeyMaxCdrSerializedSize()); // Object that serializes the data. eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); p_type->serializeKey(ser); - if (force_md5 || CarlaEgoVehicleControl::getKeyMaxCdrSerializedSize() > 16) + if (force_md5 || CarlaV2XCustomDataList::getKeyMaxCdrSerializedSize() > 16) { m_md5.init(); m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); @@ -168,5 +169,8 @@ namespace carla_msgs { } return true; } + + } //End of namespace msg + } //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataListPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataListPubSubTypes.h new file mode 100644 index 00000000000..fba673efa29 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataListPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XCustomDataListPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATALIST_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATALIST_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaV2XCustomDataList.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaV2XCustomDataList is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CarlaV2XCustomDataList defined by the user in the IDL file. + * @ingroup CARLAV2XCUSTOMDATALIST + */ + class CarlaV2XCustomDataListPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaV2XCustomDataList type; + + eProsima_user_DllExport CarlaV2XCustomDataListPubSubType(); + + eProsima_user_DllExport virtual ~CarlaV2XCustomDataListPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATALIST_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataPubSubTypes.cxx new file mode 100644 index 00000000000..ed8788995cf --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XCustomDataPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaV2XCustomDataPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaV2XCustomDataPubSubType::CarlaV2XCustomDataPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaV2XCustomData_"); + auto type_size = CarlaV2XCustomData::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaV2XCustomData::isKeyDefined(); + size_t keyLength = CarlaV2XCustomData::getKeyMaxCdrSerializedSize() > 16 ? + CarlaV2XCustomData::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaV2XCustomDataPubSubType::~CarlaV2XCustomDataPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaV2XCustomDataPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaV2XCustomData* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaV2XCustomDataPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaV2XCustomData* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaV2XCustomDataPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaV2XCustomDataPubSubType::createData() + { + return reinterpret_cast(new CarlaV2XCustomData()); + } + + void CarlaV2XCustomDataPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaV2XCustomDataPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaV2XCustomData* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaV2XCustomData::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaV2XCustomData::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataPubSubTypes.h new file mode 100644 index 00000000000..7fc1b67991d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XCustomDataPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATA_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATA_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaV2XCustomData.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaV2XCustomData is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CarlaV2XCustomData defined by the user in the IDL file. + * @ingroup CARLAV2XCUSTOMDATA + */ + class CarlaV2XCustomDataPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaV2XCustomData type; + + eProsima_user_DllExport CarlaV2XCustomDataPubSubType(); + + eProsima_user_DllExport virtual ~CarlaV2XCustomDataPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) CarlaV2XCustomData(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATA_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessage.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessage.cxx new file mode 100644 index 00000000000..68d63e62954 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessage.cxx @@ -0,0 +1,238 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XCustomMessage.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaV2XCustomMessage.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaV2XCustomMessage::CarlaV2XCustomMessage() +{ + // m_header com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@3de8f619 + + // m_data com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@2ab4bc72 + + +} + +carla_msgs::msg::CarlaV2XCustomMessage::~CarlaV2XCustomMessage() +{ + +} + +carla_msgs::msg::CarlaV2XCustomMessage::CarlaV2XCustomMessage( + const CarlaV2XCustomMessage& x) +{ + m_header = x.m_header; + m_data = x.m_data; +} + +carla_msgs::msg::CarlaV2XCustomMessage::CarlaV2XCustomMessage( + CarlaV2XCustomMessage&& x) +{ + m_header = std::move(x.m_header); + m_data = std::move(x.m_data); +} + +carla_msgs::msg::CarlaV2XCustomMessage& carla_msgs::msg::CarlaV2XCustomMessage::operator =( + const CarlaV2XCustomMessage& x) +{ + + m_header = x.m_header; + m_data = x.m_data; + + return *this; +} + +carla_msgs::msg::CarlaV2XCustomMessage& carla_msgs::msg::CarlaV2XCustomMessage::operator =( + CarlaV2XCustomMessage&& x) +{ + + m_header = std::move(x.m_header); + m_data = std::move(x.m_data); + + return *this; +} + +bool carla_msgs::msg::CarlaV2XCustomMessage::operator ==( + const CarlaV2XCustomMessage& x) const +{ + + return (m_header == x.m_header && m_data == x.m_data); +} + +bool carla_msgs::msg::CarlaV2XCustomMessage::operator !=( + const CarlaV2XCustomMessage& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaV2XCustomMessage::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::ItsPduHeader::getMaxCdrSerializedSize(current_alignment); + current_alignment += carla_msgs::msg::CarlaV2XByteArray::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaV2XCustomMessage::getCdrSerializedSize( + const carla_msgs::msg::CarlaV2XCustomMessage& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::ItsPduHeader::getCdrSerializedSize(data.header(), current_alignment); + current_alignment += carla_msgs::msg::CarlaV2XByteArray::getCdrSerializedSize(data.data(), current_alignment); + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaV2XCustomMessage::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_header; + scdr << m_data; + +} + +void carla_msgs::msg::CarlaV2XCustomMessage::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_header; + dcdr >> m_data; +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void carla_msgs::msg::CarlaV2XCustomMessage::header( + const etsi_its_cam_msgs::msg::ItsPduHeader& _header) +{ + m_header = _header; +} + +/*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ +void carla_msgs::msg::CarlaV2XCustomMessage::header( + etsi_its_cam_msgs::msg::ItsPduHeader&& _header) +{ + m_header = std::move(_header); +} + +/*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ +const etsi_its_cam_msgs::msg::ItsPduHeader& carla_msgs::msg::CarlaV2XCustomMessage::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +etsi_its_cam_msgs::msg::ItsPduHeader& carla_msgs::msg::CarlaV2XCustomMessage::header() +{ + return m_header; +} +/*! + * @brief This function copies the value in member data + * @param _data New value to be copied in member data + */ +void carla_msgs::msg::CarlaV2XCustomMessage::data( + const carla_msgs::msg::CarlaV2XByteArray& _data) +{ + m_data = _data; +} + +/*! + * @brief This function moves the value in member data + * @param _data New value to be moved in member data + */ +void carla_msgs::msg::CarlaV2XCustomMessage::data( + carla_msgs::msg::CarlaV2XByteArray&& _data) +{ + m_data = std::move(_data); +} + +/*! + * @brief This function returns a constant reference to member data + * @return Constant reference to member data + */ +const carla_msgs::msg::CarlaV2XByteArray& carla_msgs::msg::CarlaV2XCustomMessage::data() const +{ + return m_data; +} + +/*! + * @brief This function returns a reference to member data + * @return Reference to member data + */ +carla_msgs::msg::CarlaV2XByteArray& carla_msgs::msg::CarlaV2XCustomMessage::data() +{ + return m_data; +} + +size_t carla_msgs::msg::CarlaV2XCustomMessage::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaV2XCustomMessage::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaV2XCustomMessage::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessage.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessage.h new file mode 100644 index 00000000000..a922fc393a0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessage.h @@ -0,0 +1,244 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XCustomMessage.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMMESSAGE_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMMESSAGE_H_ + +#include "etsi_its_cam_msgs/msg/ItsPduHeader.h" +#include "CarlaV2XByteArray.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CarlaV2XCustomMessage_SOURCE) +#define CarlaV2XCustomMessage_DllAPI __declspec( dllexport ) +#else +#define CarlaV2XCustomMessage_DllAPI __declspec( dllimport ) +#endif // CarlaV2XCustomMessage_SOURCE +#else +#define CarlaV2XCustomMessage_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CarlaV2XCustomMessage_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace msg { + /*! + * @brief This class represents the structure CarlaV2XCustomMessage defined by the user in the IDL file. + * @ingroup CARLAV2XCUSTOMMESSAGE + */ + class CarlaV2XCustomMessage + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaV2XCustomMessage(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaV2XCustomMessage(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaV2XCustomMessage that will be copied. + */ + eProsima_user_DllExport CarlaV2XCustomMessage( + const CarlaV2XCustomMessage& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaV2XCustomMessage that will be copied. + */ + eProsima_user_DllExport CarlaV2XCustomMessage( + CarlaV2XCustomMessage&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaV2XCustomMessage that will be copied. + */ + eProsima_user_DllExport CarlaV2XCustomMessage& operator =( + const CarlaV2XCustomMessage& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaV2XCustomMessage that will be copied. + */ + eProsima_user_DllExport CarlaV2XCustomMessage& operator =( + CarlaV2XCustomMessage&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaV2XCustomMessage object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaV2XCustomMessage& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaV2XCustomMessage object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaV2XCustomMessage& x) const; + + /*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ + eProsima_user_DllExport void header( + const etsi_its_cam_msgs::msg::ItsPduHeader& _header); + + /*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ + eProsima_user_DllExport void header( + etsi_its_cam_msgs::msg::ItsPduHeader&& _header); + + /*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::ItsPduHeader& header() const; + + /*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::ItsPduHeader& header(); + /*! + * @brief This function copies the value in member data + * @param _data New value to be copied in member data + */ + eProsima_user_DllExport void data( + const carla_msgs::msg::CarlaV2XByteArray& _data); + + /*! + * @brief This function moves the value in member data + * @param _data New value to be moved in member data + */ + eProsima_user_DllExport void data( + carla_msgs::msg::CarlaV2XByteArray&& _data); + + /*! + * @brief This function returns a constant reference to member data + * @return Constant reference to member data + */ + eProsima_user_DllExport const carla_msgs::msg::CarlaV2XByteArray& data() const; + + /*! + * @brief This function returns a reference to member data + * @return Reference to member data + */ + eProsima_user_DllExport carla_msgs::msg::CarlaV2XByteArray& data(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::msg::CarlaV2XCustomMessage& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::ItsPduHeader m_header; + carla_msgs::msg::CarlaV2XByteArray m_data; + }; + } // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMMESSAGE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessagePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessagePubSubTypes.cxx new file mode 100644 index 00000000000..873197c3293 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessagePubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XCustomMessagePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaV2XCustomMessagePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaV2XCustomMessagePubSubType::CarlaV2XCustomMessagePubSubType() + { + setName("carla_msgs::msg::dds_::CarlaV2XCustomMessage_"); + auto type_size = CarlaV2XCustomMessage::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaV2XCustomMessage::isKeyDefined(); + size_t keyLength = CarlaV2XCustomMessage::getKeyMaxCdrSerializedSize() > 16 ? + CarlaV2XCustomMessage::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaV2XCustomMessagePubSubType::~CarlaV2XCustomMessagePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaV2XCustomMessagePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaV2XCustomMessage* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaV2XCustomMessagePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaV2XCustomMessage* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaV2XCustomMessagePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaV2XCustomMessagePubSubType::createData() + { + return reinterpret_cast(new CarlaV2XCustomMessage()); + } + + void CarlaV2XCustomMessagePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaV2XCustomMessagePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaV2XCustomMessage* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaV2XCustomMessage::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaV2XCustomMessage::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessagePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessagePubSubTypes.h new file mode 100644 index 00000000000..77c8d6cafde --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessagePubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XCustomMessagePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMMESSAGE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMMESSAGE_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaV2XCustomMessage.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaV2XCustomMessage is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CarlaV2XCustomMessage defined by the user in the IDL file. + * @ingroup CARLAV2XCUSTOMMESSAGE + */ + class CarlaV2XCustomMessagePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaV2XCustomMessage type; + + eProsima_user_DllExport CarlaV2XCustomMessagePubSubType(); + + eProsima_user_DllExport virtual ~CarlaV2XCustomMessagePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) CarlaV2XCustomMessage(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMMESSAGE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomPubSubTypes.cxx new file mode 100644 index 00000000000..83520b6d783 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XCustomPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaV2XCustomPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaV2XCustomPubSubType::CarlaV2XCustomPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaV2XCustom_"); + auto type_size = CarlaV2XCustom::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaV2XCustom::isKeyDefined(); + size_t keyLength = CarlaV2XCustom::getKeyMaxCdrSerializedSize() > 16 ? + CarlaV2XCustom::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaV2XCustomPubSubType::~CarlaV2XCustomPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaV2XCustomPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaV2XCustom* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaV2XCustomPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaV2XCustom* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaV2XCustomPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaV2XCustomPubSubType::createData() + { + return reinterpret_cast(new CarlaV2XCustom()); + } + + void CarlaV2XCustomPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaV2XCustomPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaV2XCustom* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaV2XCustom::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaV2XCustom::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomPubSubTypes.h new file mode 100644 index 00000000000..5f8f40b70fb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XCustomPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOM_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOM_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaV2XCustom.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaV2XCustom is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CarlaV2XCustom defined by the user in the IDL file. + * @ingroup CARLAV2XCUSTOM + */ + class CarlaV2XCustomPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaV2XCustom type; + + eProsima_user_DllExport CarlaV2XCustomPubSubType(); + + eProsima_user_DllExport virtual ~CarlaV2XCustomPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOM_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XData.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XData.cxx new file mode 100644 index 00000000000..d47aa161353 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XData.cxx @@ -0,0 +1,233 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XData.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaV2XData.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaV2XData::CarlaV2XData() +{ + // m_power com.eprosima.idl.parser.typecode.PrimitiveTypeCode@f1da57d + m_power = 0.0; + // m_message com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@72c8e7b + + +} + +carla_msgs::msg::CarlaV2XData::~CarlaV2XData() +{ + +} + +carla_msgs::msg::CarlaV2XData::CarlaV2XData( + const CarlaV2XData& x) +{ + m_power = x.m_power; + m_message = x.m_message; +} + +carla_msgs::msg::CarlaV2XData::CarlaV2XData( + CarlaV2XData&& x) +{ + m_power = x.m_power; + m_message = std::move(x.m_message); +} + +carla_msgs::msg::CarlaV2XData& carla_msgs::msg::CarlaV2XData::operator =( + const CarlaV2XData& x) +{ + + m_power = x.m_power; + m_message = x.m_message; + + return *this; +} + +carla_msgs::msg::CarlaV2XData& carla_msgs::msg::CarlaV2XData::operator =( + CarlaV2XData&& x) +{ + + m_power = x.m_power; + m_message = std::move(x.m_message); + + return *this; +} + +bool carla_msgs::msg::CarlaV2XData::operator ==( + const CarlaV2XData& x) const +{ + + return (m_power == x.m_power && m_message == x.m_message); +} + +bool carla_msgs::msg::CarlaV2XData::operator !=( + const CarlaV2XData& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaV2XData::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += etsi_its_cam_msgs::msg::CAM::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaV2XData::getCdrSerializedSize( + const carla_msgs::msg::CarlaV2XData& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += etsi_its_cam_msgs::msg::CAM::getCdrSerializedSize(data.message(), current_alignment); + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaV2XData::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_power; + scdr << m_message; + +} + +void carla_msgs::msg::CarlaV2XData::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_power; + dcdr >> m_message; +} + +/*! + * @brief This function sets a value in member power + * @param _power New value for member power + */ +void carla_msgs::msg::CarlaV2XData::power( + float _power) +{ + m_power = _power; +} + +/*! + * @brief This function returns the value of member power + * @return Value of member power + */ +float carla_msgs::msg::CarlaV2XData::power() const +{ + return m_power; +} + +/*! + * @brief This function returns a reference to member power + * @return Reference to member power + */ +float& carla_msgs::msg::CarlaV2XData::power() +{ + return m_power; +} + +/*! + * @brief This function copies the value in member message + * @param _message New value to be copied in member message + */ +void carla_msgs::msg::CarlaV2XData::message( + const etsi_its_cam_msgs::msg::CAM& _message) +{ + m_message = _message; +} + +/*! + * @brief This function moves the value in member message + * @param _message New value to be moved in member message + */ +void carla_msgs::msg::CarlaV2XData::message( + etsi_its_cam_msgs::msg::CAM&& _message) +{ + m_message = std::move(_message); +} + +/*! + * @brief This function returns a constant reference to member message + * @return Constant reference to member message + */ +const etsi_its_cam_msgs::msg::CAM& carla_msgs::msg::CarlaV2XData::message() const +{ + return m_message; +} + +/*! + * @brief This function returns a reference to member message + * @return Reference to member message + */ +etsi_its_cam_msgs::msg::CAM& carla_msgs::msg::CarlaV2XData::message() +{ + return m_message; +} + +size_t carla_msgs::msg::CarlaV2XData::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaV2XData::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaV2XData::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/types/NavSatStatus.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XData.h similarity index 55% rename from LibCarla/source/carla/ros2/types/NavSatStatus.h rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XData.h index df69678aee5..55f36360acb 100644 --- a/LibCarla/source/carla/ros2/types/NavSatStatus.h +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XData.h @@ -13,16 +13,16 @@ // limitations under the License. /*! - * @file NavSatStatus.h + * @file CarlaV2XData.h * This header file contains the declaration of the described types in the IDL file. * * This file was generated by the tool gen. */ -#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUS_H_ -#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUS_H_ +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATA_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATA_H_ -#include +#include "etsi_its_cam_msgs/msg/CAM.h" #include #include @@ -43,16 +43,16 @@ #if defined(_WIN32) #if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(NavSatStatus_SOURCE) -#define NavSatStatus_DllAPI __declspec( dllexport ) +#if defined(CarlaV2XData_SOURCE) +#define CarlaV2XData_DllAPI __declspec( dllexport ) #else -#define NavSatStatus_DllAPI __declspec( dllimport ) -#endif // NavSatStatus_SOURCE +#define CarlaV2XData_DllAPI __declspec( dllimport ) +#endif // CarlaV2XData_SOURCE #else -#define NavSatStatus_DllAPI +#define CarlaV2XData_DllAPI #endif // EPROSIMA_USER_DLL_EXPORT #else -#define NavSatStatus_DllAPI +#define CarlaV2XData_DllAPI #endif // _WIN32 namespace eprosima { @@ -61,120 +61,120 @@ class Cdr; } // namespace fastcdr } // namespace eprosima -namespace sensor_msgs { + +namespace carla_msgs { namespace msg { - const uint8_t NavSatStatus__STATUS_NO_FIX = 255; - const uint8_t NavSatStatus__STATUS_FIX = 0; - const uint8_t NavSatStatus__STATUS_SBAS_FIX = 1; - const uint8_t NavSatStatus__STATUS_GBAS_FIX = 2; - const uint16_t NavSatStatus__SERVICE_GPS = 1; - const uint16_t NavSatStatus__SERVICE_GLONASS = 2; - const uint16_t NavSatStatus__SERVICE_COMPASS = 4; - const uint16_t NavSatStatus__SERVICE_GALILEO = 8; /*! - * @brief This class represents the structure NavSatStatus defined by the user in the IDL file. - * @ingroup NAVSATSTATUS + * @brief This class represents the structure CarlaV2XData defined by the user in the IDL file. + * @ingroup CARLAV2XDATA */ - class NavSatStatus + class CarlaV2XData { public: /*! * @brief Default constructor. */ - eProsima_user_DllExport NavSatStatus(); + eProsima_user_DllExport CarlaV2XData(); /*! * @brief Default destructor. */ - eProsima_user_DllExport ~NavSatStatus(); + eProsima_user_DllExport ~CarlaV2XData(); /*! * @brief Copy constructor. - * @param x Reference to the object sensor_msgs::msg::NavSatStatus that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaV2XData that will be copied. */ - eProsima_user_DllExport NavSatStatus( - const NavSatStatus& x); + eProsima_user_DllExport CarlaV2XData( + const CarlaV2XData& x); /*! * @brief Move constructor. - * @param x Reference to the object sensor_msgs::msg::NavSatStatus that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaV2XData that will be copied. */ - eProsima_user_DllExport NavSatStatus( - NavSatStatus&& x) noexcept; + eProsima_user_DllExport CarlaV2XData( + CarlaV2XData&& x); /*! * @brief Copy assignment. - * @param x Reference to the object sensor_msgs::msg::NavSatStatus that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaV2XData that will be copied. */ - eProsima_user_DllExport NavSatStatus& operator =( - const NavSatStatus& x); + eProsima_user_DllExport CarlaV2XData& operator =( + const CarlaV2XData& x); /*! * @brief Move assignment. - * @param x Reference to the object sensor_msgs::msg::NavSatStatus that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaV2XData that will be copied. */ - eProsima_user_DllExport NavSatStatus& operator =( - NavSatStatus&& x) noexcept; + eProsima_user_DllExport CarlaV2XData& operator =( + CarlaV2XData&& x); /*! * @brief Comparison operator. - * @param x sensor_msgs::msg::NavSatStatus object to compare. + * @param x carla_msgs::msg::CarlaV2XData object to compare. */ eProsima_user_DllExport bool operator ==( - const NavSatStatus& x) const; + const CarlaV2XData& x) const; /*! * @brief Comparison operator. - * @param x sensor_msgs::msg::NavSatStatus object to compare. + * @param x carla_msgs::msg::CarlaV2XData object to compare. */ eProsima_user_DllExport bool operator !=( - const NavSatStatus& x) const; + const CarlaV2XData& x) const; + + /*! + * @brief This function sets a value in member power + * @param _power New value for member power + */ + eProsima_user_DllExport void power( + float _power); /*! - * @brief This function sets a value in member status - * @param _status New value for member status + * @brief This function returns the value of member power + * @return Value of member power */ - eProsima_user_DllExport void status( - uint8_t _status); + eProsima_user_DllExport float power() const; /*! - * @brief This function returns the value of member status - * @return Value of member status + * @brief This function returns a reference to member power + * @return Reference to member power */ - eProsima_user_DllExport uint8_t status() const; + eProsima_user_DllExport float& power(); /*! - * @brief This function returns a reference to member status - * @return Reference to member status + * @brief This function copies the value in member message + * @param _message New value to be copied in member message */ - eProsima_user_DllExport uint8_t& status(); + eProsima_user_DllExport void message( + const etsi_its_cam_msgs::msg::CAM& _message); /*! - * @brief This function sets a value in member service - * @param _service New value for member service + * @brief This function moves the value in member message + * @param _message New value to be moved in member message */ - eProsima_user_DllExport void service( - uint16_t _service); + eProsima_user_DllExport void message( + etsi_its_cam_msgs::msg::CAM&& _message); /*! - * @brief This function returns the value of member service - * @return Value of member service + * @brief This function returns a constant reference to member message + * @return Constant reference to member message */ - eProsima_user_DllExport uint16_t service() const; + eProsima_user_DllExport const etsi_its_cam_msgs::msg::CAM& message() const; /*! - * @brief This function returns a reference to member service - * @return Reference to member service + * @brief This function returns a reference to member message + * @return Reference to member message */ - eProsima_user_DllExport uint16_t& service(); + eProsima_user_DllExport etsi_its_cam_msgs::msg::CAM& message(); /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -185,9 +185,10 @@ namespace sensor_msgs { * @return Serialized size. */ eProsima_user_DllExport static size_t getCdrSerializedSize( - const sensor_msgs::msg::NavSatStatus& data, + const carla_msgs::msg::CarlaV2XData& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -202,6 +203,8 @@ namespace sensor_msgs { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -224,10 +227,11 @@ namespace sensor_msgs { eprosima::fastcdr::Cdr& cdr) const; private: - uint8_t m_status; - uint16_t m_service; + + float m_power; + etsi_its_cam_msgs::msg::CAM m_message; }; } // namespace msg -} // namespace sensor_msgs +} // namespace carla_msgs -#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUS_H_ +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATA_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataList.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataList.cxx new file mode 100644 index 00000000000..dbe4e1b9de1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataList.cxx @@ -0,0 +1,198 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XDataList.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaV2XDataList.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaV2XDataList::CarlaV2XDataList() +{ + // m_data com.eprosima.idl.parser.typecode.SequenceTypeCode@60f00693 + + +} + +carla_msgs::msg::CarlaV2XDataList::~CarlaV2XDataList() +{ +} + +carla_msgs::msg::CarlaV2XDataList::CarlaV2XDataList( + const CarlaV2XDataList& x) +{ + m_data = x.m_data; +} + +carla_msgs::msg::CarlaV2XDataList::CarlaV2XDataList( + CarlaV2XDataList&& x) +{ + m_data = std::move(x.m_data); +} + +carla_msgs::msg::CarlaV2XDataList& carla_msgs::msg::CarlaV2XDataList::operator =( + const CarlaV2XDataList& x) +{ + + m_data = x.m_data; + + return *this; +} + +carla_msgs::msg::CarlaV2XDataList& carla_msgs::msg::CarlaV2XDataList::operator =( + CarlaV2XDataList&& x) +{ + + m_data = std::move(x.m_data); + + return *this; +} + +bool carla_msgs::msg::CarlaV2XDataList::operator ==( + const CarlaV2XDataList& x) const +{ + + return (m_data == x.m_data); +} + +bool carla_msgs::msg::CarlaV2XDataList::operator !=( + const CarlaV2XDataList& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaV2XDataList::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < 100; ++a) + { + current_alignment += carla_msgs::msg::CarlaV2XData::getMaxCdrSerializedSize(current_alignment);} + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaV2XDataList::getCdrSerializedSize( + const carla_msgs::msg::CarlaV2XDataList& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < data.data().size(); ++a) + { + current_alignment += carla_msgs::msg::CarlaV2XData::getCdrSerializedSize(data.data().at(a), current_alignment);} + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaV2XDataList::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_data; +} + +void carla_msgs::msg::CarlaV2XDataList::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_data;} + +/*! + * @brief This function copies the value in member data + * @param _data New value to be copied in member data + */ +void carla_msgs::msg::CarlaV2XDataList::data( + const std::vector& _data) +{ + m_data = _data; +} + +/*! + * @brief This function moves the value in member data + * @param _data New value to be moved in member data + */ +void carla_msgs::msg::CarlaV2XDataList::data( + std::vector&& _data) +{ + m_data = std::move(_data); +} + +/*! + * @brief This function returns a constant reference to member data + * @return Constant reference to member data + */ +const std::vector& carla_msgs::msg::CarlaV2XDataList::data() const +{ + return m_data; +} + +/*! + * @brief This function returns a reference to member data + * @return Reference to member data + */ +std::vector& carla_msgs::msg::CarlaV2XDataList::data() +{ + return m_data; +} + +size_t carla_msgs::msg::CarlaV2XDataList::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaV2XDataList::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaV2XDataList::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/types/String.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataList.h similarity index 65% rename from LibCarla/source/carla/ros2/types/String.h rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataList.h index 1c99d0d8a2d..c223f5f2e55 100644 --- a/LibCarla/source/carla/ros2/types/String.h +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataList.h @@ -13,16 +13,16 @@ // limitations under the License. /*! - * @file String.h + * @file CarlaV2XDataList.h * This header file contains the declaration of the described types in the IDL file. * * This file was generated by the tool gen. */ -#ifndef _FAST_DDS_GENERATED_STD_MSGS_MSG_STRING_H_ -#define _FAST_DDS_GENERATED_STD_MSGS_MSG_STRING_H_ +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATALIST_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATALIST_H_ -#include +#include "CarlaV2XData.h" #include #include @@ -43,16 +43,16 @@ #if defined(_WIN32) #if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(String_SOURCE) -#define String_DllAPI __declspec( dllexport ) +#if defined(CarlaV2XDataList_SOURCE) +#define CarlaV2XDataList_DllAPI __declspec( dllexport ) #else -#define String_DllAPI __declspec( dllimport ) -#endif // String_SOURCE +#define CarlaV2XDataList_DllAPI __declspec( dllimport ) +#endif // CarlaV2XDataList_SOURCE #else -#define String_DllAPI +#define CarlaV2XDataList_DllAPI #endif // EPROSIMA_USER_DLL_EXPORT #else -#define String_DllAPI +#define CarlaV2XDataList_DllAPI #endif // _WIN32 namespace eprosima { @@ -61,100 +61,101 @@ class Cdr; } // namespace fastcdr } // namespace eprosima -namespace std_msgs { + +namespace carla_msgs { namespace msg { /*! - * @brief This class represents the structure String defined by the user in the IDL file. - * @ingroup STRING + * @brief This class represents the structure CarlaV2XDataList defined by the user in the IDL file. + * @ingroup CARLAV2XDATALIST */ - class String + class CarlaV2XDataList { public: /*! * @brief Default constructor. */ - eProsima_user_DllExport String(); + eProsima_user_DllExport CarlaV2XDataList(); /*! * @brief Default destructor. */ - eProsima_user_DllExport ~String(); + eProsima_user_DllExport ~CarlaV2XDataList(); /*! * @brief Copy constructor. - * @param x Reference to the object std_msgs::msg::String that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaV2XDataList that will be copied. */ - eProsima_user_DllExport String( - const String& x); + eProsima_user_DllExport CarlaV2XDataList( + const CarlaV2XDataList& x); /*! * @brief Move constructor. - * @param x Reference to the object std_msgs::msg::String that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaV2XDataList that will be copied. */ - eProsima_user_DllExport String( - String&& x) noexcept; + eProsima_user_DllExport CarlaV2XDataList( + CarlaV2XDataList&& x); /*! * @brief Copy assignment. - * @param x Reference to the object std_msgs::msg::String that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaV2XDataList that will be copied. */ - eProsima_user_DllExport String& operator =( - const String& x); + eProsima_user_DllExport CarlaV2XDataList& operator =( + const CarlaV2XDataList& x); /*! * @brief Move assignment. - * @param x Reference to the object std_msgs::msg::String that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaV2XDataList that will be copied. */ - eProsima_user_DllExport String& operator =( - String&& x) noexcept; + eProsima_user_DllExport CarlaV2XDataList& operator =( + CarlaV2XDataList&& x); /*! * @brief Comparison operator. - * @param x std_msgs::msg::String object to compare. + * @param x carla_msgs::msg::CarlaV2XDataList object to compare. */ eProsima_user_DllExport bool operator ==( - const String& x) const; + const CarlaV2XDataList& x) const; /*! * @brief Comparison operator. - * @param x std_msgs::msg::String object to compare. + * @param x carla_msgs::msg::CarlaV2XDataList object to compare. */ eProsima_user_DllExport bool operator !=( - const String& x) const; + const CarlaV2XDataList& x) const; /*! * @brief This function copies the value in member data * @param _data New value to be copied in member data */ eProsima_user_DllExport void data( - const std::string& _data); + const std::vector& _data); /*! * @brief This function moves the value in member data * @param _data New value to be moved in member data */ eProsima_user_DllExport void data( - std::string&& _data); + std::vector&& _data); /*! * @brief This function returns a constant reference to member data * @return Constant reference to member data */ - eProsima_user_DllExport const std::string& data() const; + eProsima_user_DllExport const std::vector& data() const; /*! * @brief This function returns a reference to member data * @return Reference to member data */ - eProsima_user_DllExport std::string& data(); + eProsima_user_DllExport std::vector& data(); /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -165,9 +166,10 @@ namespace std_msgs { * @return Serialized size. */ eProsima_user_DllExport static size_t getCdrSerializedSize( - const std_msgs::msg::String& data, + const carla_msgs::msg::CarlaV2XDataList& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -182,6 +184,8 @@ namespace std_msgs { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -204,9 +208,10 @@ namespace std_msgs { eprosima::fastcdr::Cdr& cdr) const; private: - std::string m_data; + + std::vector m_data; }; } // namespace msg -} // namespace std_msgs +} // namespace carla_msgs -#endif // _FAST_DDS_GENERATED_STD_MSGS_MSG_STRING_H_ +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATALIST_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataListPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataListPubSubTypes.cxx new file mode 100644 index 00000000000..6fa29800f84 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataListPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XDataListPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaV2XDataListPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaV2XDataListPubSubType::CarlaV2XDataListPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaV2XDataList_"); + auto type_size = CarlaV2XDataList::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaV2XDataList::isKeyDefined(); + size_t keyLength = CarlaV2XDataList::getKeyMaxCdrSerializedSize() > 16 ? + CarlaV2XDataList::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaV2XDataListPubSubType::~CarlaV2XDataListPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaV2XDataListPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaV2XDataList* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaV2XDataListPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaV2XDataList* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaV2XDataListPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaV2XDataListPubSubType::createData() + { + return reinterpret_cast(new CarlaV2XDataList()); + } + + void CarlaV2XDataListPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaV2XDataListPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaV2XDataList* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaV2XDataList::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaV2XDataList::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/types/TransformStampedPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataListPubSubTypes.h similarity index 78% rename from LibCarla/source/carla/ros2/types/TransformStampedPubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataListPubSubTypes.h index 7bd5a9b400f..787738b46c3 100644 --- a/LibCarla/source/carla/ros2/types/TransformStampedPubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataListPubSubTypes.h @@ -13,46 +13,43 @@ // limitations under the License. /*! - * @file TransformStampedPubSubTypes.h + * @file CarlaV2XDataListPubSubTypes.h * This header file contains the declaration of the serialization functions. * * This file was generated by the tool fastcdrgen. */ -#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPED_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPED_PUBSUBTYPES_H_ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATALIST_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATALIST_PUBSUBTYPES_H_ #include #include -#include "TransformStamped.h" - -#include "HeaderPubSubTypes.h" -#include "TransformPubSubTypes.h" +#include "CarlaV2XDataList.h" #if !defined(GEN_API_VER) || (GEN_API_VER != 1) #error \ - Generated TransformStamped is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. + Generated CarlaV2XDataList is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. #endif // GEN_API_VER -namespace geometry_msgs +namespace carla_msgs { namespace msg { - /*! - * @brief This class represents the TopicDataType of the type TransformStamped defined by the user in the IDL file. - * @ingroup TRANSFORMSTAMPED + * @brief This class represents the TopicDataType of the type CarlaV2XDataList defined by the user in the IDL file. + * @ingroup CARLAV2XDATALIST */ - class TransformStampedPubSubType : public eprosima::fastdds::dds::TopicDataType + class CarlaV2XDataListPubSubType : public eprosima::fastdds::dds::TopicDataType { public: - typedef TransformStamped type; + typedef CarlaV2XDataList type; - eProsima_user_DllExport TransformStampedPubSubType(); + eProsima_user_DllExport CarlaV2XDataListPubSubType(); - eProsima_user_DllExport virtual ~TransformStampedPubSubType() override; + eProsima_user_DllExport virtual ~CarlaV2XDataListPubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -100,10 +97,11 @@ namespace geometry_msgs } #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; unsigned char* m_keyBuffer; }; } } -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPED_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATALIST_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataPubSubTypes.cxx new file mode 100644 index 00000000000..43a907f6064 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaV2XDataPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaV2XDataPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaV2XDataPubSubType::CarlaV2XDataPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaV2XData_"); + auto type_size = CarlaV2XData::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaV2XData::isKeyDefined(); + size_t keyLength = CarlaV2XData::getKeyMaxCdrSerializedSize() > 16 ? + CarlaV2XData::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaV2XDataPubSubType::~CarlaV2XDataPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaV2XDataPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaV2XData* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaV2XDataPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaV2XData* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaV2XDataPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaV2XDataPubSubType::createData() + { + return reinterpret_cast(new CarlaV2XData()); + } + + void CarlaV2XDataPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaV2XDataPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaV2XData* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaV2XData::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaV2XData::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/types/StringPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataPubSubTypes.h similarity index 78% rename from LibCarla/source/carla/ros2/types/StringPubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataPubSubTypes.h index 749abb654c6..d073f9fbc41 100644 --- a/LibCarla/source/carla/ros2/types/StringPubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataPubSubTypes.h @@ -13,43 +13,43 @@ // limitations under the License. /*! - * @file StringPubSubTypes.h + * @file CarlaV2XDataPubSubTypes.h * This header file contains the declaration of the serialization functions. * * This file was generated by the tool fastcdrgen. */ -#ifndef _FAST_DDS_GENERATED_STD_MSGS_MSG_STRING_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_STD_MSGS_MSG_STRING_PUBSUBTYPES_H_ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATA_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATA_PUBSUBTYPES_H_ #include #include -#include "String.h" +#include "CarlaV2XData.h" #if !defined(GEN_API_VER) || (GEN_API_VER != 1) #error \ - Generated String is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. + Generated CarlaV2XData is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. #endif // GEN_API_VER -namespace std_msgs +namespace carla_msgs { namespace msg { - /*! - * @brief This class represents the TopicDataType of the type String defined by the user in the IDL file. - * @ingroup STRING + * @brief This class represents the TopicDataType of the type CarlaV2XData defined by the user in the IDL file. + * @ingroup CARLAV2XDATA */ - class StringPubSubType : public eprosima::fastdds::dds::TopicDataType + class CarlaV2XDataPubSubType : public eprosima::fastdds::dds::TopicDataType { public: - typedef String type; + typedef CarlaV2XData type; - eProsima_user_DllExport StringPubSubType(); + eProsima_user_DllExport CarlaV2XDataPubSubType(); - eProsima_user_DllExport virtual ~StringPubSubType() override; + eProsima_user_DllExport virtual ~CarlaV2XDataPubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -97,10 +97,11 @@ namespace std_msgs } #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; unsigned char* m_keyBuffer; }; } } -#endif // _FAST_DDS_GENERATED_STD_MSGS_MSG_STRING_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATA_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/CarlaEgoVehicleControl.cpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControl.cxx similarity index 57% rename from LibCarla/source/carla/ros2/types/CarlaEgoVehicleControl.cpp rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControl.cxx index 2c1eb165ef5..5f1b97bd76e 100644 --- a/LibCarla/source/carla/ros2/types/CarlaEgoVehicleControl.cpp +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControl.cxx @@ -13,7 +13,7 @@ // limitations under the License. /*! - * @file CarlaEgoCarlaEgoVehicleControl.cpp + * @file CarlaVehicleControl.cpp * This source file contains the definition of the described types in the IDL file. * * This file was generated by the tool gen. @@ -26,7 +26,7 @@ char dummy; } // namespace #endif // _WIN32 -#include "CarlaEgoVehicleControl.h" +#include "CarlaVehicleControl.h" #include #include @@ -34,40 +34,43 @@ using namespace eprosima::fastcdr::exception; #include -#define builtin_interfaces_msg_Time_max_cdr_typesize 8ULL; -#define std_msgs_msg_Header_max_cdr_typesize 268ULL; -#define carla_msgs_msg_CarlaEgoVehicleControl_max_cdr_typesize 289ULL; -#define builtin_interfaces_msg_Time_max_key_cdr_typesize 0ULL; -#define std_msgs_msg_Header_max_key_cdr_typesize 0ULL; -#define carla_msgs_msg_CarlaEgoVehicleControl_max_key_cdr_typesize 0ULL; - -carla_msgs::msg::CarlaEgoVehicleControl::CarlaEgoVehicleControl() +carla_msgs::msg::CarlaVehicleControl::CarlaVehicleControl() { - // std_msgs::msg::Header m_header + // m_header com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@62ddbd7e - // float m_throttle + // m_throttle com.eprosima.idl.parser.typecode.PrimitiveTypeCode@74e52ef6 m_throttle = 0.0; - // float m_steer + // m_steer com.eprosima.idl.parser.typecode.PrimitiveTypeCode@6ed3ccb2 m_steer = 0.0; - // float m_brake + // m_brake com.eprosima.idl.parser.typecode.PrimitiveTypeCode@1a677343 m_brake = 0.0; - // boolean m_hand_brake + // m_hand_brake com.eprosima.idl.parser.typecode.PrimitiveTypeCode@15de0b3c m_hand_brake = false; - // boolean m_reverse + // m_reverse com.eprosima.idl.parser.typecode.PrimitiveTypeCode@489115ef m_reverse = false; - // long m_gear + // m_gear com.eprosima.idl.parser.typecode.PrimitiveTypeCode@3857f613 m_gear = 0; - // boolean m_manual_gear_shift + // m_manual_gear_shift com.eprosima.idl.parser.typecode.PrimitiveTypeCode@3c9754d8 m_manual_gear_shift = false; + // m_control_priority com.eprosima.idl.parser.typecode.PrimitiveTypeCode@3bf7ca37 + m_control_priority = 4; } -carla_msgs::msg::CarlaEgoVehicleControl::~CarlaEgoVehicleControl() +carla_msgs::msg::CarlaVehicleControl::~CarlaVehicleControl() { + + + + + + + + } -carla_msgs::msg::CarlaEgoVehicleControl::CarlaEgoVehicleControl( - const CarlaEgoVehicleControl& x) +carla_msgs::msg::CarlaVehicleControl::CarlaVehicleControl( + const CarlaVehicleControl& x) { m_header = x.m_header; m_throttle = x.m_throttle; @@ -77,10 +80,11 @@ carla_msgs::msg::CarlaEgoVehicleControl::CarlaEgoVehicleControl( m_reverse = x.m_reverse; m_gear = x.m_gear; m_manual_gear_shift = x.m_manual_gear_shift; + m_control_priority = x.m_control_priority; } -carla_msgs::msg::CarlaEgoVehicleControl::CarlaEgoVehicleControl( - CarlaEgoVehicleControl&& x) noexcept +carla_msgs::msg::CarlaVehicleControl::CarlaVehicleControl( + CarlaVehicleControl&& x) { m_header = std::move(x.m_header); m_throttle = x.m_throttle; @@ -90,11 +94,13 @@ carla_msgs::msg::CarlaEgoVehicleControl::CarlaEgoVehicleControl( m_reverse = x.m_reverse; m_gear = x.m_gear; m_manual_gear_shift = x.m_manual_gear_shift; + m_control_priority = x.m_control_priority; } -carla_msgs::msg::CarlaEgoVehicleControl& carla_msgs::msg::CarlaEgoVehicleControl::operator =( - const CarlaEgoVehicleControl& x) +carla_msgs::msg::CarlaVehicleControl& carla_msgs::msg::CarlaVehicleControl::operator =( + const CarlaVehicleControl& x) { + m_header = x.m_header; m_throttle = x.m_throttle; m_steer = x.m_steer; @@ -103,13 +109,15 @@ carla_msgs::msg::CarlaEgoVehicleControl& carla_msgs::msg::CarlaEgoVehicleControl m_reverse = x.m_reverse; m_gear = x.m_gear; m_manual_gear_shift = x.m_manual_gear_shift; + m_control_priority = x.m_control_priority; return *this; } -carla_msgs::msg::CarlaEgoVehicleControl& carla_msgs::msg::CarlaEgoVehicleControl::operator =( - CarlaEgoVehicleControl&& x) noexcept +carla_msgs::msg::CarlaVehicleControl& carla_msgs::msg::CarlaVehicleControl::operator =( + CarlaVehicleControl&& x) { + m_header = std::move(x.m_header); m_throttle = x.m_throttle; m_steer = x.m_steer; @@ -118,48 +126,100 @@ carla_msgs::msg::CarlaEgoVehicleControl& carla_msgs::msg::CarlaEgoVehicleControl m_reverse = x.m_reverse; m_gear = x.m_gear; m_manual_gear_shift = x.m_manual_gear_shift; + m_control_priority = x.m_control_priority; return *this; } -bool carla_msgs::msg::CarlaEgoVehicleControl::operator ==( - const CarlaEgoVehicleControl& x) const +bool carla_msgs::msg::CarlaVehicleControl::operator ==( + const CarlaVehicleControl& x) const { - return (m_header == x.m_header && m_throttle == x.m_throttle && m_steer == x.m_steer && m_brake == x.m_brake && m_hand_brake == x.m_hand_brake && m_reverse == x.m_reverse && m_gear == x.m_gear && m_manual_gear_shift == x.m_manual_gear_shift); + + return (m_header == x.m_header && m_throttle == x.m_throttle && m_steer == x.m_steer && m_brake == x.m_brake && m_hand_brake == x.m_hand_brake && m_reverse == x.m_reverse && m_gear == x.m_gear && m_manual_gear_shift == x.m_manual_gear_shift && m_control_priority == x.m_control_priority); } -bool carla_msgs::msg::CarlaEgoVehicleControl::operator !=( - const CarlaEgoVehicleControl& x) const +bool carla_msgs::msg::CarlaVehicleControl::operator !=( + const CarlaVehicleControl& x) const { return !(*this == x); } -size_t carla_msgs::msg::CarlaEgoVehicleControl::getMaxCdrSerializedSize( +size_t carla_msgs::msg::CarlaVehicleControl::getMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return carla_msgs_msg_CarlaEgoVehicleControl_max_cdr_typesize; + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getMaxCdrSerializedSize(current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; } -size_t carla_msgs::msg::CarlaEgoVehicleControl::getCdrSerializedSize( - const carla_msgs::msg::CarlaEgoVehicleControl& data, +size_t carla_msgs::msg::CarlaVehicleControl::getCdrSerializedSize( + const carla_msgs::msg::CarlaVehicleControl& data, size_t current_alignment) { + (void)data; size_t initial_alignment = current_alignment; + + current_alignment += std_msgs::msg::Header::getCdrSerializedSize(data.header(), current_alignment); current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; } -void carla_msgs::msg::CarlaEgoVehicleControl::serialize( +void carla_msgs::msg::CarlaVehicleControl::serialize( eprosima::fastcdr::Cdr& scdr) const { + scdr << m_header; scdr << m_throttle; scdr << m_steer; @@ -168,11 +228,14 @@ void carla_msgs::msg::CarlaEgoVehicleControl::serialize( scdr << m_reverse; scdr << m_gear; scdr << m_manual_gear_shift; + scdr << m_control_priority; + } -void carla_msgs::msg::CarlaEgoVehicleControl::deserialize( +void carla_msgs::msg::CarlaVehicleControl::deserialize( eprosima::fastcdr::Cdr& dcdr) { + dcdr >> m_header; dcdr >> m_throttle; dcdr >> m_steer; @@ -181,13 +244,14 @@ void carla_msgs::msg::CarlaEgoVehicleControl::deserialize( dcdr >> m_reverse; dcdr >> m_gear; dcdr >> m_manual_gear_shift; + dcdr >> m_control_priority; } /*! * @brief This function copies the value in member header * @param _header New value to be copied in member header */ -void carla_msgs::msg::CarlaEgoVehicleControl::header( +void carla_msgs::msg::CarlaVehicleControl::header( const std_msgs::msg::Header& _header) { m_header = _header; @@ -197,7 +261,7 @@ void carla_msgs::msg::CarlaEgoVehicleControl::header( * @brief This function moves the value in member header * @param _header New value to be moved in member header */ -void carla_msgs::msg::CarlaEgoVehicleControl::header( +void carla_msgs::msg::CarlaVehicleControl::header( std_msgs::msg::Header&& _header) { m_header = std::move(_header); @@ -207,7 +271,7 @@ void carla_msgs::msg::CarlaEgoVehicleControl::header( * @brief This function returns a constant reference to member header * @return Constant reference to member header */ -const std_msgs::msg::Header& carla_msgs::msg::CarlaEgoVehicleControl::header() const +const std_msgs::msg::Header& carla_msgs::msg::CarlaVehicleControl::header() const { return m_header; } @@ -216,7 +280,7 @@ const std_msgs::msg::Header& carla_msgs::msg::CarlaEgoVehicleControl::header() c * @brief This function returns a reference to member header * @return Reference to member header */ -std_msgs::msg::Header& carla_msgs::msg::CarlaEgoVehicleControl::header() +std_msgs::msg::Header& carla_msgs::msg::CarlaVehicleControl::header() { return m_header; } @@ -224,7 +288,7 @@ std_msgs::msg::Header& carla_msgs::msg::CarlaEgoVehicleControl::header() * @brief This function sets a value in member throttle * @param _throttle New value for member throttle */ -void carla_msgs::msg::CarlaEgoVehicleControl::throttle( +void carla_msgs::msg::CarlaVehicleControl::throttle( float _throttle) { m_throttle = _throttle; @@ -234,7 +298,7 @@ void carla_msgs::msg::CarlaEgoVehicleControl::throttle( * @brief This function returns the value of member throttle * @return Value of member throttle */ -float carla_msgs::msg::CarlaEgoVehicleControl::throttle() const +float carla_msgs::msg::CarlaVehicleControl::throttle() const { return m_throttle; } @@ -243,7 +307,7 @@ float carla_msgs::msg::CarlaEgoVehicleControl::throttle() const * @brief This function returns a reference to member throttle * @return Reference to member throttle */ -float& carla_msgs::msg::CarlaEgoVehicleControl::throttle() +float& carla_msgs::msg::CarlaVehicleControl::throttle() { return m_throttle; } @@ -252,7 +316,7 @@ float& carla_msgs::msg::CarlaEgoVehicleControl::throttle() * @brief This function sets a value in member steer * @param _steer New value for member steer */ -void carla_msgs::msg::CarlaEgoVehicleControl::steer( +void carla_msgs::msg::CarlaVehicleControl::steer( float _steer) { m_steer = _steer; @@ -262,7 +326,7 @@ void carla_msgs::msg::CarlaEgoVehicleControl::steer( * @brief This function returns the value of member steer * @return Value of member steer */ -float carla_msgs::msg::CarlaEgoVehicleControl::steer() const +float carla_msgs::msg::CarlaVehicleControl::steer() const { return m_steer; } @@ -271,7 +335,7 @@ float carla_msgs::msg::CarlaEgoVehicleControl::steer() const * @brief This function returns a reference to member steer * @return Reference to member steer */ -float& carla_msgs::msg::CarlaEgoVehicleControl::steer() +float& carla_msgs::msg::CarlaVehicleControl::steer() { return m_steer; } @@ -280,7 +344,7 @@ float& carla_msgs::msg::CarlaEgoVehicleControl::steer() * @brief This function sets a value in member brake * @param _brake New value for member brake */ -void carla_msgs::msg::CarlaEgoVehicleControl::brake( +void carla_msgs::msg::CarlaVehicleControl::brake( float _brake) { m_brake = _brake; @@ -290,7 +354,7 @@ void carla_msgs::msg::CarlaEgoVehicleControl::brake( * @brief This function returns the value of member brake * @return Value of member brake */ -float carla_msgs::msg::CarlaEgoVehicleControl::brake() const +float carla_msgs::msg::CarlaVehicleControl::brake() const { return m_brake; } @@ -299,7 +363,7 @@ float carla_msgs::msg::CarlaEgoVehicleControl::brake() const * @brief This function returns a reference to member brake * @return Reference to member brake */ -float& carla_msgs::msg::CarlaEgoVehicleControl::brake() +float& carla_msgs::msg::CarlaVehicleControl::brake() { return m_brake; } @@ -308,7 +372,7 @@ float& carla_msgs::msg::CarlaEgoVehicleControl::brake() * @brief This function sets a value in member hand_brake * @param _hand_brake New value for member hand_brake */ -void carla_msgs::msg::CarlaEgoVehicleControl::hand_brake( +void carla_msgs::msg::CarlaVehicleControl::hand_brake( bool _hand_brake) { m_hand_brake = _hand_brake; @@ -318,7 +382,7 @@ void carla_msgs::msg::CarlaEgoVehicleControl::hand_brake( * @brief This function returns the value of member hand_brake * @return Value of member hand_brake */ -bool carla_msgs::msg::CarlaEgoVehicleControl::hand_brake() const +bool carla_msgs::msg::CarlaVehicleControl::hand_brake() const { return m_hand_brake; } @@ -327,7 +391,7 @@ bool carla_msgs::msg::CarlaEgoVehicleControl::hand_brake() const * @brief This function returns a reference to member hand_brake * @return Reference to member hand_brake */ -bool& carla_msgs::msg::CarlaEgoVehicleControl::hand_brake() +bool& carla_msgs::msg::CarlaVehicleControl::hand_brake() { return m_hand_brake; } @@ -336,7 +400,7 @@ bool& carla_msgs::msg::CarlaEgoVehicleControl::hand_brake() * @brief This function sets a value in member reverse * @param _reverse New value for member reverse */ -void carla_msgs::msg::CarlaEgoVehicleControl::reverse( +void carla_msgs::msg::CarlaVehicleControl::reverse( bool _reverse) { m_reverse = _reverse; @@ -346,7 +410,7 @@ void carla_msgs::msg::CarlaEgoVehicleControl::reverse( * @brief This function returns the value of member reverse * @return Value of member reverse */ -bool carla_msgs::msg::CarlaEgoVehicleControl::reverse() const +bool carla_msgs::msg::CarlaVehicleControl::reverse() const { return m_reverse; } @@ -355,7 +419,7 @@ bool carla_msgs::msg::CarlaEgoVehicleControl::reverse() const * @brief This function returns a reference to member reverse * @return Reference to member reverse */ -bool& carla_msgs::msg::CarlaEgoVehicleControl::reverse() +bool& carla_msgs::msg::CarlaVehicleControl::reverse() { return m_reverse; } @@ -364,7 +428,7 @@ bool& carla_msgs::msg::CarlaEgoVehicleControl::reverse() * @brief This function sets a value in member gear * @param _gear New value for member gear */ -void carla_msgs::msg::CarlaEgoVehicleControl::gear( +void carla_msgs::msg::CarlaVehicleControl::gear( int32_t _gear) { m_gear = _gear; @@ -374,7 +438,7 @@ void carla_msgs::msg::CarlaEgoVehicleControl::gear( * @brief This function returns the value of member gear * @return Value of member gear */ -int32_t carla_msgs::msg::CarlaEgoVehicleControl::gear() const +int32_t carla_msgs::msg::CarlaVehicleControl::gear() const { return m_gear; } @@ -383,7 +447,7 @@ int32_t carla_msgs::msg::CarlaEgoVehicleControl::gear() const * @brief This function returns a reference to member gear * @return Reference to member gear */ -int32_t& carla_msgs::msg::CarlaEgoVehicleControl::gear() +int32_t& carla_msgs::msg::CarlaVehicleControl::gear() { return m_gear; } @@ -392,7 +456,7 @@ int32_t& carla_msgs::msg::CarlaEgoVehicleControl::gear() * @brief This function sets a value in member manual_gear_shift * @param _manual_gear_shift New value for member manual_gear_shift */ -void carla_msgs::msg::CarlaEgoVehicleControl::manual_gear_shift( +void carla_msgs::msg::CarlaVehicleControl::manual_gear_shift( bool _manual_gear_shift) { m_manual_gear_shift = _manual_gear_shift; @@ -402,7 +466,7 @@ void carla_msgs::msg::CarlaEgoVehicleControl::manual_gear_shift( * @brief This function returns the value of member manual_gear_shift * @return Value of member manual_gear_shift */ -bool carla_msgs::msg::CarlaEgoVehicleControl::manual_gear_shift() const +bool carla_msgs::msg::CarlaVehicleControl::manual_gear_shift() const { return m_manual_gear_shift; } @@ -411,25 +475,60 @@ bool carla_msgs::msg::CarlaEgoVehicleControl::manual_gear_shift() const * @brief This function returns a reference to member manual_gear_shift * @return Reference to member manual_gear_shift */ -bool& carla_msgs::msg::CarlaEgoVehicleControl::manual_gear_shift() +bool& carla_msgs::msg::CarlaVehicleControl::manual_gear_shift() { return m_manual_gear_shift; } -size_t carla_msgs::msg::CarlaEgoVehicleControl::getKeyMaxCdrSerializedSize( +/*! + * @brief This function sets a value in member control_priority + * @param _control_priority New value for member control_priority + */ +void carla_msgs::msg::CarlaVehicleControl::control_priority( + uint8_t _control_priority) +{ + m_control_priority = _control_priority; +} + +/*! + * @brief This function returns the value of member control_priority + * @return Value of member control_priority + */ +uint8_t carla_msgs::msg::CarlaVehicleControl::control_priority() const +{ + return m_control_priority; +} + +/*! + * @brief This function returns a reference to member control_priority + * @return Reference to member control_priority + */ +uint8_t& carla_msgs::msg::CarlaVehicleControl::control_priority() +{ + return m_control_priority; +} + + +size_t carla_msgs::msg::CarlaVehicleControl::getKeyMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return carla_msgs_msg_CarlaEgoVehicleControl_max_key_cdr_typesize; + size_t current_align = current_alignment; + + + + return current_align; } -bool carla_msgs::msg::CarlaEgoVehicleControl::isKeyDefined() +bool carla_msgs::msg::CarlaVehicleControl::isKeyDefined() { return false; } -void carla_msgs::msg::CarlaEgoVehicleControl::serializeKey( +void carla_msgs::msg::CarlaVehicleControl::serializeKey( eprosima::fastcdr::Cdr& scdr) const { (void) scdr; + } + + diff --git a/LibCarla/source/carla/ros2/types/CarlaEgoVehicleControl.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControl.h similarity index 78% rename from LibCarla/source/carla/ros2/types/CarlaEgoVehicleControl.h rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControl.h index f941d5dcb41..6f11cbe5a54 100644 --- a/LibCarla/source/carla/ros2/types/CarlaEgoVehicleControl.h +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControl.h @@ -13,18 +13,16 @@ // limitations under the License. /*! - * @file CarlaEgoCarlaEgoVehicleControl.h + * @file CarlaVehicleControl.h * This header file contains the declaration of the described types in the IDL file. * * This file was generated by the tool gen. */ -#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOCarlaEgoVehicleControl_H_ -#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOCarlaEgoVehicleControl_H_ +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLECONTROL_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLECONTROL_H_ -#include "Header.h" - -#include +#include "std_msgs/msg/Header.h" #include #include @@ -45,16 +43,16 @@ #if defined(_WIN32) #if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(CarlaEgoCarlaEgoVehicleControl_SOURCE) -#define CarlaEgoCarlaEgoVehicleControl_DllAPI __declspec( dllexport ) +#if defined(CarlaVehicleControl_SOURCE) +#define CarlaVehicleControl_DllAPI __declspec( dllexport ) #else -#define CarlaEgoCarlaEgoVehicleControl_DllAPI __declspec( dllimport ) -#endif // CarlaEgoCarlaEgoVehicleControl_SOURCE +#define CarlaVehicleControl_DllAPI __declspec( dllimport ) +#endif // CarlaVehicleControl_SOURCE #else -#define CarlaEgoCarlaEgoVehicleControl_DllAPI +#define CarlaVehicleControl_DllAPI #endif // EPROSIMA_USER_DLL_EXPORT #else -#define CarlaEgoCarlaEgoVehicleControl_DllAPI +#define CarlaVehicleControl_DllAPI #endif // _WIN32 namespace eprosima { @@ -63,67 +61,68 @@ class Cdr; } // namespace fastcdr } // namespace eprosima + namespace carla_msgs { namespace msg { /*! - * @brief This class represents the structure CarlaEgoVehicleControl defined by the user in the IDL file. - * @ingroup CarlaEgoVehicleControl + * @brief This class represents the structure CarlaVehicleControl defined by the user in the IDL file. + * @ingroup CARLAVEHICLECONTROL */ - class CarlaEgoVehicleControl + class CarlaVehicleControl { public: /*! * @brief Default constructor. */ - eProsima_user_DllExport CarlaEgoVehicleControl(); + eProsima_user_DllExport CarlaVehicleControl(); /*! * @brief Default destructor. */ - eProsima_user_DllExport ~CarlaEgoVehicleControl(); + eProsima_user_DllExport ~CarlaVehicleControl(); /*! * @brief Copy constructor. - * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleControl that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleControl that will be copied. */ - eProsima_user_DllExport CarlaEgoVehicleControl( - const CarlaEgoVehicleControl& x); + eProsima_user_DllExport CarlaVehicleControl( + const CarlaVehicleControl& x); /*! * @brief Move constructor. - * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleControl that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleControl that will be copied. */ - eProsima_user_DllExport CarlaEgoVehicleControl( - CarlaEgoVehicleControl&& x) noexcept; + eProsima_user_DllExport CarlaVehicleControl( + CarlaVehicleControl&& x); /*! * @brief Copy assignment. - * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleControl that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleControl that will be copied. */ - eProsima_user_DllExport CarlaEgoVehicleControl& operator =( - const CarlaEgoVehicleControl& x); + eProsima_user_DllExport CarlaVehicleControl& operator =( + const CarlaVehicleControl& x); /*! * @brief Move assignment. - * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleControl that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleControl that will be copied. */ - eProsima_user_DllExport CarlaEgoVehicleControl& operator =( - CarlaEgoVehicleControl&& x) noexcept; + eProsima_user_DllExport CarlaVehicleControl& operator =( + CarlaVehicleControl&& x); /*! * @brief Comparison operator. - * @param x carla_msgs::msg::CarlaEgoVehicleControl object to compare. + * @param x carla_msgs::msg::CarlaVehicleControl object to compare. */ eProsima_user_DllExport bool operator ==( - const CarlaEgoVehicleControl& x) const; + const CarlaVehicleControl& x) const; /*! * @brief Comparison operator. - * @param x carla_msgs::msg::CarlaEgoVehicleControl object to compare. + * @param x carla_msgs::msg::CarlaVehicleControl object to compare. */ eProsima_user_DllExport bool operator !=( - const CarlaEgoVehicleControl& x) const; + const CarlaVehicleControl& x) const; /*! * @brief This function copies the value in member header @@ -284,11 +283,31 @@ namespace carla_msgs { eProsima_user_DllExport bool& manual_gear_shift(); /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ + * @brief This function sets a value in member control_priority + * @param _control_priority New value for member control_priority + */ + eProsima_user_DllExport void control_priority( + uint8_t _control_priority); + + /*! + * @brief This function returns the value of member control_priority + * @return Value of member control_priority + */ + eProsima_user_DllExport uint8_t control_priority() const; + + /*! + * @brief This function returns a reference to member control_priority + * @return Reference to member control_priority + */ + eProsima_user_DllExport uint8_t& control_priority(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -299,9 +318,10 @@ namespace carla_msgs { * @return Serialized size. */ eProsima_user_DllExport static size_t getCdrSerializedSize( - const carla_msgs::msg::CarlaEgoVehicleControl& data, + const carla_msgs::msg::CarlaVehicleControl& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -316,6 +336,8 @@ namespace carla_msgs { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -338,6 +360,7 @@ namespace carla_msgs { eprosima::fastcdr::Cdr& cdr) const; private: + std_msgs::msg::Header m_header; float m_throttle; float m_steer; @@ -346,9 +369,9 @@ namespace carla_msgs { bool m_reverse; int32_t m_gear; bool m_manual_gear_shift; - + uint8_t m_control_priority; }; } // namespace msg } // namespace carla_msgs -#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOCarlaEgoVehicleControl_H_ +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLECONTROL_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControlPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControlPubSubTypes.cxx new file mode 100644 index 00000000000..0e36309faba --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControlPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleControlPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaVehicleControlPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaVehicleControlPubSubType::CarlaVehicleControlPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaVehicleControl_"); + auto type_size = CarlaVehicleControl::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaVehicleControl::isKeyDefined(); + size_t keyLength = CarlaVehicleControl::getKeyMaxCdrSerializedSize() > 16 ? + CarlaVehicleControl::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaVehicleControlPubSubType::~CarlaVehicleControlPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaVehicleControlPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaVehicleControl* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaVehicleControlPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaVehicleControl* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaVehicleControlPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaVehicleControlPubSubType::createData() + { + return reinterpret_cast(new CarlaVehicleControl()); + } + + void CarlaVehicleControlPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaVehicleControlPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaVehicleControl* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaVehicleControl::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaVehicleControl::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControlPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControlPubSubTypes.h new file mode 100644 index 00000000000..b0081b30d4e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControlPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleControlPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLECONTROL_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLECONTROL_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaVehicleControl.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaVehicleControl is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CarlaVehicleControl defined by the user in the IDL file. + * @ingroup CARLAVEHICLECONTROL + */ + class CarlaVehicleControlPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaVehicleControl type; + + eProsima_user_DllExport CarlaVehicleControlPubSubType(); + + eProsima_user_DllExport virtual ~CarlaVehicleControlPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLECONTROL_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControlStatus.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControlStatus.cxx new file mode 100644 index 00000000000..725030a3352 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControlStatus.cxx @@ -0,0 +1,284 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleControlStatus.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaVehicleControlStatus.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + +carla_msgs::msg::CarlaVehicleControlStatus::CarlaVehicleControlStatus() +{ + // m_active_control_type com.eprosima.idl.parser.typecode.PrimitiveTypeCode@120f102b + m_active_control_type = 0; + // m_last_applied_vehicle_control com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@625732 + + // m_last_applied_ackermann_control com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@51dcb805 + + +} + +carla_msgs::msg::CarlaVehicleControlStatus::~CarlaVehicleControlStatus() +{ + + +} + +carla_msgs::msg::CarlaVehicleControlStatus::CarlaVehicleControlStatus( + const CarlaVehicleControlStatus& x) +{ + m_active_control_type = x.m_active_control_type; + m_last_applied_vehicle_control = x.m_last_applied_vehicle_control; + m_last_applied_ackermann_control = x.m_last_applied_ackermann_control; +} + +carla_msgs::msg::CarlaVehicleControlStatus::CarlaVehicleControlStatus( + CarlaVehicleControlStatus&& x) +{ + m_active_control_type = x.m_active_control_type; + m_last_applied_vehicle_control = std::move(x.m_last_applied_vehicle_control); + m_last_applied_ackermann_control = std::move(x.m_last_applied_ackermann_control); +} + +carla_msgs::msg::CarlaVehicleControlStatus& carla_msgs::msg::CarlaVehicleControlStatus::operator =( + const CarlaVehicleControlStatus& x) +{ + + m_active_control_type = x.m_active_control_type; + m_last_applied_vehicle_control = x.m_last_applied_vehicle_control; + m_last_applied_ackermann_control = x.m_last_applied_ackermann_control; + + return *this; +} + +carla_msgs::msg::CarlaVehicleControlStatus& carla_msgs::msg::CarlaVehicleControlStatus::operator =( + CarlaVehicleControlStatus&& x) +{ + + m_active_control_type = x.m_active_control_type; + m_last_applied_vehicle_control = std::move(x.m_last_applied_vehicle_control); + m_last_applied_ackermann_control = std::move(x.m_last_applied_ackermann_control); + + return *this; +} + +bool carla_msgs::msg::CarlaVehicleControlStatus::operator ==( + const CarlaVehicleControlStatus& x) const +{ + + return (m_active_control_type == x.m_active_control_type && m_last_applied_vehicle_control == x.m_last_applied_vehicle_control && m_last_applied_ackermann_control == x.m_last_applied_ackermann_control); +} + +bool carla_msgs::msg::CarlaVehicleControlStatus::operator !=( + const CarlaVehicleControlStatus& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaVehicleControlStatus::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += carla_msgs::msg::CarlaVehicleControl::getMaxCdrSerializedSize(current_alignment); + current_alignment += ackermann_msgs::msg::AckermannDriveStamped::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaVehicleControlStatus::getCdrSerializedSize( + const carla_msgs::msg::CarlaVehicleControlStatus& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += carla_msgs::msg::CarlaVehicleControl::getCdrSerializedSize(data.last_applied_vehicle_control(), current_alignment); + current_alignment += ackermann_msgs::msg::AckermannDriveStamped::getCdrSerializedSize(data.last_applied_ackermann_control(), current_alignment); + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaVehicleControlStatus::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_active_control_type; + scdr << m_last_applied_vehicle_control; + scdr << m_last_applied_ackermann_control; + +} + +void carla_msgs::msg::CarlaVehicleControlStatus::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_active_control_type; + dcdr >> m_last_applied_vehicle_control; + dcdr >> m_last_applied_ackermann_control; +} + +/*! + * @brief This function sets a value in member active_control_type + * @param _active_control_type New value for member active_control_type + */ +void carla_msgs::msg::CarlaVehicleControlStatus::active_control_type( + uint8_t _active_control_type) +{ + m_active_control_type = _active_control_type; +} + +/*! + * @brief This function returns the value of member active_control_type + * @return Value of member active_control_type + */ +uint8_t carla_msgs::msg::CarlaVehicleControlStatus::active_control_type() const +{ + return m_active_control_type; +} + +/*! + * @brief This function returns a reference to member active_control_type + * @return Reference to member active_control_type + */ +uint8_t& carla_msgs::msg::CarlaVehicleControlStatus::active_control_type() +{ + return m_active_control_type; +} + +/*! + * @brief This function copies the value in member last_applied_vehicle_control + * @param _last_applied_vehicle_control New value to be copied in member last_applied_vehicle_control + */ +void carla_msgs::msg::CarlaVehicleControlStatus::last_applied_vehicle_control( + const carla_msgs::msg::CarlaVehicleControl& _last_applied_vehicle_control) +{ + m_last_applied_vehicle_control = _last_applied_vehicle_control; +} + +/*! + * @brief This function moves the value in member last_applied_vehicle_control + * @param _last_applied_vehicle_control New value to be moved in member last_applied_vehicle_control + */ +void carla_msgs::msg::CarlaVehicleControlStatus::last_applied_vehicle_control( + carla_msgs::msg::CarlaVehicleControl&& _last_applied_vehicle_control) +{ + m_last_applied_vehicle_control = std::move(_last_applied_vehicle_control); +} + +/*! + * @brief This function returns a constant reference to member last_applied_vehicle_control + * @return Constant reference to member last_applied_vehicle_control + */ +const carla_msgs::msg::CarlaVehicleControl& carla_msgs::msg::CarlaVehicleControlStatus::last_applied_vehicle_control() const +{ + return m_last_applied_vehicle_control; +} + +/*! + * @brief This function returns a reference to member last_applied_vehicle_control + * @return Reference to member last_applied_vehicle_control + */ +carla_msgs::msg::CarlaVehicleControl& carla_msgs::msg::CarlaVehicleControlStatus::last_applied_vehicle_control() +{ + return m_last_applied_vehicle_control; +} +/*! + * @brief This function copies the value in member last_applied_ackermann_control + * @param _last_applied_ackermann_control New value to be copied in member last_applied_ackermann_control + */ +void carla_msgs::msg::CarlaVehicleControlStatus::last_applied_ackermann_control( + const ackermann_msgs::msg::AckermannDriveStamped& _last_applied_ackermann_control) +{ + m_last_applied_ackermann_control = _last_applied_ackermann_control; +} + +/*! + * @brief This function moves the value in member last_applied_ackermann_control + * @param _last_applied_ackermann_control New value to be moved in member last_applied_ackermann_control + */ +void carla_msgs::msg::CarlaVehicleControlStatus::last_applied_ackermann_control( + ackermann_msgs::msg::AckermannDriveStamped&& _last_applied_ackermann_control) +{ + m_last_applied_ackermann_control = std::move(_last_applied_ackermann_control); +} + +/*! + * @brief This function returns a constant reference to member last_applied_ackermann_control + * @return Constant reference to member last_applied_ackermann_control + */ +const ackermann_msgs::msg::AckermannDriveStamped& carla_msgs::msg::CarlaVehicleControlStatus::last_applied_ackermann_control() const +{ + return m_last_applied_ackermann_control; +} + +/*! + * @brief This function returns a reference to member last_applied_ackermann_control + * @return Reference to member last_applied_ackermann_control + */ +ackermann_msgs::msg::AckermannDriveStamped& carla_msgs::msg::CarlaVehicleControlStatus::last_applied_ackermann_control() +{ + return m_last_applied_ackermann_control; +} + +size_t carla_msgs::msg::CarlaVehicleControlStatus::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaVehicleControlStatus::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaVehicleControlStatus::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControlStatus.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControlStatus.h new file mode 100644 index 00000000000..8a12f1361fa --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControlStatus.h @@ -0,0 +1,268 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleControlStatus.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLECONTROLSTATUS_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLECONTROLSTATUS_H_ + +#include "CarlaVehicleControl.h" +#include "ackermann_msgs/msg/AckermannDriveStamped.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CarlaVehicleControlStatus_SOURCE) +#define CarlaVehicleControlStatus_DllAPI __declspec( dllexport ) +#else +#define CarlaVehicleControlStatus_DllAPI __declspec( dllimport ) +#endif // CarlaVehicleControlStatus_SOURCE +#else +#define CarlaVehicleControlStatus_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CarlaVehicleControlStatus_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace msg { + namespace CarlaVehicleControlStatus_Constants { + const uint8_t VEHICLE_CONTROL = 0; + const uint8_t ACKERMANN_CONTROL = 1; + } // namespace CarlaVehicleControlStatus_Constants + /*! + * @brief This class represents the structure CarlaVehicleControlStatus defined by the user in the IDL file. + * @ingroup CARLAVEHICLECONTROLSTATUS + */ + class CarlaVehicleControlStatus + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaVehicleControlStatus(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaVehicleControlStatus(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleControlStatus that will be copied. + */ + eProsima_user_DllExport CarlaVehicleControlStatus( + const CarlaVehicleControlStatus& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleControlStatus that will be copied. + */ + eProsima_user_DllExport CarlaVehicleControlStatus( + CarlaVehicleControlStatus&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleControlStatus that will be copied. + */ + eProsima_user_DllExport CarlaVehicleControlStatus& operator =( + const CarlaVehicleControlStatus& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleControlStatus that will be copied. + */ + eProsima_user_DllExport CarlaVehicleControlStatus& operator =( + CarlaVehicleControlStatus&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaVehicleControlStatus object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaVehicleControlStatus& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaVehicleControlStatus object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaVehicleControlStatus& x) const; + + /*! + * @brief This function sets a value in member active_control_type + * @param _active_control_type New value for member active_control_type + */ + eProsima_user_DllExport void active_control_type( + uint8_t _active_control_type); + + /*! + * @brief This function returns the value of member active_control_type + * @return Value of member active_control_type + */ + eProsima_user_DllExport uint8_t active_control_type() const; + + /*! + * @brief This function returns a reference to member active_control_type + * @return Reference to member active_control_type + */ + eProsima_user_DllExport uint8_t& active_control_type(); + + /*! + * @brief This function copies the value in member last_applied_vehicle_control + * @param _last_applied_vehicle_control New value to be copied in member last_applied_vehicle_control + */ + eProsima_user_DllExport void last_applied_vehicle_control( + const carla_msgs::msg::CarlaVehicleControl& _last_applied_vehicle_control); + + /*! + * @brief This function moves the value in member last_applied_vehicle_control + * @param _last_applied_vehicle_control New value to be moved in member last_applied_vehicle_control + */ + eProsima_user_DllExport void last_applied_vehicle_control( + carla_msgs::msg::CarlaVehicleControl&& _last_applied_vehicle_control); + + /*! + * @brief This function returns a constant reference to member last_applied_vehicle_control + * @return Constant reference to member last_applied_vehicle_control + */ + eProsima_user_DllExport const carla_msgs::msg::CarlaVehicleControl& last_applied_vehicle_control() const; + + /*! + * @brief This function returns a reference to member last_applied_vehicle_control + * @return Reference to member last_applied_vehicle_control + */ + eProsima_user_DllExport carla_msgs::msg::CarlaVehicleControl& last_applied_vehicle_control(); + /*! + * @brief This function copies the value in member last_applied_ackermann_control + * @param _last_applied_ackermann_control New value to be copied in member last_applied_ackermann_control + */ + eProsima_user_DllExport void last_applied_ackermann_control( + const ackermann_msgs::msg::AckermannDriveStamped& _last_applied_ackermann_control); + + /*! + * @brief This function moves the value in member last_applied_ackermann_control + * @param _last_applied_ackermann_control New value to be moved in member last_applied_ackermann_control + */ + eProsima_user_DllExport void last_applied_ackermann_control( + ackermann_msgs::msg::AckermannDriveStamped&& _last_applied_ackermann_control); + + /*! + * @brief This function returns a constant reference to member last_applied_ackermann_control + * @return Constant reference to member last_applied_ackermann_control + */ + eProsima_user_DllExport const ackermann_msgs::msg::AckermannDriveStamped& last_applied_ackermann_control() const; + + /*! + * @brief This function returns a reference to member last_applied_ackermann_control + * @return Reference to member last_applied_ackermann_control + */ + eProsima_user_DllExport ackermann_msgs::msg::AckermannDriveStamped& last_applied_ackermann_control(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::msg::CarlaVehicleControlStatus& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_active_control_type; + carla_msgs::msg::CarlaVehicleControl m_last_applied_vehicle_control; + ackermann_msgs::msg::AckermannDriveStamped m_last_applied_ackermann_control; + }; + } // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLECONTROLSTATUS_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControlStatusPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControlStatusPubSubTypes.cxx new file mode 100644 index 00000000000..5830e6f7d0e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControlStatusPubSubTypes.cxx @@ -0,0 +1,181 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleControlStatusPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaVehicleControlStatusPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + namespace CarlaVehicleControlStatus_Constants { + + + + } //End of namespace CarlaVehicleControlStatus_Constants + CarlaVehicleControlStatusPubSubType::CarlaVehicleControlStatusPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaVehicleControlStatus_"); + auto type_size = CarlaVehicleControlStatus::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaVehicleControlStatus::isKeyDefined(); + size_t keyLength = CarlaVehicleControlStatus::getKeyMaxCdrSerializedSize() > 16 ? + CarlaVehicleControlStatus::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaVehicleControlStatusPubSubType::~CarlaVehicleControlStatusPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaVehicleControlStatusPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaVehicleControlStatus* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaVehicleControlStatusPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaVehicleControlStatus* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaVehicleControlStatusPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaVehicleControlStatusPubSubType::createData() + { + return reinterpret_cast(new CarlaVehicleControlStatus()); + } + + void CarlaVehicleControlStatusPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaVehicleControlStatusPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaVehicleControlStatus* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaVehicleControlStatus::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaVehicleControlStatus::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControlStatusPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControlStatusPubSubTypes.h new file mode 100644 index 00000000000..efec816cf46 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleControlStatusPubSubTypes.h @@ -0,0 +1,112 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleControlStatusPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLECONTROLSTATUS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLECONTROLSTATUS_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaVehicleControlStatus.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaVehicleControlStatus is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + namespace CarlaVehicleControlStatus_Constants + { + + + } + /*! + * @brief This class represents the TopicDataType of the type CarlaVehicleControlStatus defined by the user in the IDL file. + * @ingroup CARLAVEHICLECONTROLSTATUS + */ + class CarlaVehicleControlStatusPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaVehicleControlStatus type; + + eProsima_user_DllExport CarlaVehicleControlStatusPubSubType(); + + eProsima_user_DllExport virtual ~CarlaVehicleControlStatusPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLECONTROLSTATUS_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfo.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfo.cxx new file mode 100644 index 00000000000..1ffd5c8dec4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfo.cxx @@ -0,0 +1,871 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleInfo.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaVehicleInfo.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaVehicleInfo::CarlaVehicleInfo() +{ + // m_id com.eprosima.idl.parser.typecode.PrimitiveTypeCode@53fdffa1 + m_id = 0; + // m_type com.eprosima.idl.parser.typecode.StringTypeCode@5562c41e + m_type =""; + // m_rolename com.eprosima.idl.parser.typecode.StringTypeCode@32ee6fee + m_rolename =""; + // m_wheels com.eprosima.idl.parser.typecode.SequenceTypeCode@3232a28a + + // m_max_rpm com.eprosima.idl.parser.typecode.PrimitiveTypeCode@73e22a3d + m_max_rpm = 0.0; + // m_moi com.eprosima.idl.parser.typecode.PrimitiveTypeCode@47faa49c + m_moi = 0.0; + // m_damping_rate_full_throttle com.eprosima.idl.parser.typecode.PrimitiveTypeCode@28f2a10f + m_damping_rate_full_throttle = 0.0; + // m_damping_rate_zero_throttle_clutch_engaged com.eprosima.idl.parser.typecode.PrimitiveTypeCode@f736069 + m_damping_rate_zero_throttle_clutch_engaged = 0.0; + // m_damping_rate_zero_throttle_clutch_disengaged com.eprosima.idl.parser.typecode.PrimitiveTypeCode@4229bb3f + m_damping_rate_zero_throttle_clutch_disengaged = 0.0; + // m_use_gear_autobox com.eprosima.idl.parser.typecode.PrimitiveTypeCode@56cdfb3b + m_use_gear_autobox = false; + // m_gear_switch_time com.eprosima.idl.parser.typecode.PrimitiveTypeCode@2b91004a + m_gear_switch_time = 0.0; + // m_clutch_strength com.eprosima.idl.parser.typecode.PrimitiveTypeCode@20ccf40b + m_clutch_strength = 0.0; + // m_mass com.eprosima.idl.parser.typecode.PrimitiveTypeCode@2fb3536e + m_mass = 0.0; + // m_drag_coefficient com.eprosima.idl.parser.typecode.PrimitiveTypeCode@169e6180 + m_drag_coefficient = 0.0; + // m_center_of_mass com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@35aea049 + + // m_shape com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@7205765b + + +} + +carla_msgs::msg::CarlaVehicleInfo::~CarlaVehicleInfo() +{ + + + + + + + + + + + + + + + +} + +carla_msgs::msg::CarlaVehicleInfo::CarlaVehicleInfo( + const CarlaVehicleInfo& x) +{ + m_id = x.m_id; + m_type = x.m_type; + m_rolename = x.m_rolename; + m_wheels = x.m_wheels; + m_max_rpm = x.m_max_rpm; + m_moi = x.m_moi; + m_damping_rate_full_throttle = x.m_damping_rate_full_throttle; + m_damping_rate_zero_throttle_clutch_engaged = x.m_damping_rate_zero_throttle_clutch_engaged; + m_damping_rate_zero_throttle_clutch_disengaged = x.m_damping_rate_zero_throttle_clutch_disengaged; + m_use_gear_autobox = x.m_use_gear_autobox; + m_gear_switch_time = x.m_gear_switch_time; + m_clutch_strength = x.m_clutch_strength; + m_mass = x.m_mass; + m_drag_coefficient = x.m_drag_coefficient; + m_center_of_mass = x.m_center_of_mass; + m_shape = x.m_shape; +} + +carla_msgs::msg::CarlaVehicleInfo::CarlaVehicleInfo( + CarlaVehicleInfo&& x) +{ + m_id = x.m_id; + m_type = std::move(x.m_type); + m_rolename = std::move(x.m_rolename); + m_wheels = std::move(x.m_wheels); + m_max_rpm = x.m_max_rpm; + m_moi = x.m_moi; + m_damping_rate_full_throttle = x.m_damping_rate_full_throttle; + m_damping_rate_zero_throttle_clutch_engaged = x.m_damping_rate_zero_throttle_clutch_engaged; + m_damping_rate_zero_throttle_clutch_disengaged = x.m_damping_rate_zero_throttle_clutch_disengaged; + m_use_gear_autobox = x.m_use_gear_autobox; + m_gear_switch_time = x.m_gear_switch_time; + m_clutch_strength = x.m_clutch_strength; + m_mass = x.m_mass; + m_drag_coefficient = x.m_drag_coefficient; + m_center_of_mass = std::move(x.m_center_of_mass); + m_shape = std::move(x.m_shape); +} + +carla_msgs::msg::CarlaVehicleInfo& carla_msgs::msg::CarlaVehicleInfo::operator =( + const CarlaVehicleInfo& x) +{ + + m_id = x.m_id; + m_type = x.m_type; + m_rolename = x.m_rolename; + m_wheels = x.m_wheels; + m_max_rpm = x.m_max_rpm; + m_moi = x.m_moi; + m_damping_rate_full_throttle = x.m_damping_rate_full_throttle; + m_damping_rate_zero_throttle_clutch_engaged = x.m_damping_rate_zero_throttle_clutch_engaged; + m_damping_rate_zero_throttle_clutch_disengaged = x.m_damping_rate_zero_throttle_clutch_disengaged; + m_use_gear_autobox = x.m_use_gear_autobox; + m_gear_switch_time = x.m_gear_switch_time; + m_clutch_strength = x.m_clutch_strength; + m_mass = x.m_mass; + m_drag_coefficient = x.m_drag_coefficient; + m_center_of_mass = x.m_center_of_mass; + m_shape = x.m_shape; + + return *this; +} + +carla_msgs::msg::CarlaVehicleInfo& carla_msgs::msg::CarlaVehicleInfo::operator =( + CarlaVehicleInfo&& x) +{ + + m_id = x.m_id; + m_type = std::move(x.m_type); + m_rolename = std::move(x.m_rolename); + m_wheels = std::move(x.m_wheels); + m_max_rpm = x.m_max_rpm; + m_moi = x.m_moi; + m_damping_rate_full_throttle = x.m_damping_rate_full_throttle; + m_damping_rate_zero_throttle_clutch_engaged = x.m_damping_rate_zero_throttle_clutch_engaged; + m_damping_rate_zero_throttle_clutch_disengaged = x.m_damping_rate_zero_throttle_clutch_disengaged; + m_use_gear_autobox = x.m_use_gear_autobox; + m_gear_switch_time = x.m_gear_switch_time; + m_clutch_strength = x.m_clutch_strength; + m_mass = x.m_mass; + m_drag_coefficient = x.m_drag_coefficient; + m_center_of_mass = std::move(x.m_center_of_mass); + m_shape = std::move(x.m_shape); + + return *this; +} + +bool carla_msgs::msg::CarlaVehicleInfo::operator ==( + const CarlaVehicleInfo& x) const +{ + + return (m_id == x.m_id && m_type == x.m_type && m_rolename == x.m_rolename && m_wheels == x.m_wheels && m_max_rpm == x.m_max_rpm && m_moi == x.m_moi && m_damping_rate_full_throttle == x.m_damping_rate_full_throttle && m_damping_rate_zero_throttle_clutch_engaged == x.m_damping_rate_zero_throttle_clutch_engaged && m_damping_rate_zero_throttle_clutch_disengaged == x.m_damping_rate_zero_throttle_clutch_disengaged && m_use_gear_autobox == x.m_use_gear_autobox && m_gear_switch_time == x.m_gear_switch_time && m_clutch_strength == x.m_clutch_strength && m_mass == x.m_mass && m_drag_coefficient == x.m_drag_coefficient && m_center_of_mass == x.m_center_of_mass && m_shape == x.m_shape); +} + +bool carla_msgs::msg::CarlaVehicleInfo::operator !=( + const CarlaVehicleInfo& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaVehicleInfo::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < 100; ++a) + { + current_alignment += carla_msgs::msg::CarlaVehicleInfoWheel::getMaxCdrSerializedSize(current_alignment);} + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += geometry_msgs::msg::Vector3::getMaxCdrSerializedSize(current_alignment); + current_alignment += shape_msgs::msg::SolidPrimitive::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaVehicleInfo::getCdrSerializedSize( + const carla_msgs::msg::CarlaVehicleInfo& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.type().size() + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.rolename().size() + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < data.wheels().size(); ++a) + { + current_alignment += carla_msgs::msg::CarlaVehicleInfoWheel::getCdrSerializedSize(data.wheels().at(a), current_alignment);} + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += geometry_msgs::msg::Vector3::getCdrSerializedSize(data.center_of_mass(), current_alignment); + current_alignment += shape_msgs::msg::SolidPrimitive::getCdrSerializedSize(data.shape(), current_alignment); + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaVehicleInfo::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_id; + scdr << m_type; + scdr << m_rolename; + scdr << m_wheels; + scdr << m_max_rpm; + scdr << m_moi; + scdr << m_damping_rate_full_throttle; + scdr << m_damping_rate_zero_throttle_clutch_engaged; + scdr << m_damping_rate_zero_throttle_clutch_disengaged; + scdr << m_use_gear_autobox; + scdr << m_gear_switch_time; + scdr << m_clutch_strength; + scdr << m_mass; + scdr << m_drag_coefficient; + scdr << m_center_of_mass; + scdr << m_shape; + +} + +void carla_msgs::msg::CarlaVehicleInfo::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_id; + dcdr >> m_type; + dcdr >> m_rolename; + dcdr >> m_wheels; + dcdr >> m_max_rpm; + dcdr >> m_moi; + dcdr >> m_damping_rate_full_throttle; + dcdr >> m_damping_rate_zero_throttle_clutch_engaged; + dcdr >> m_damping_rate_zero_throttle_clutch_disengaged; + dcdr >> m_use_gear_autobox; + dcdr >> m_gear_switch_time; + dcdr >> m_clutch_strength; + dcdr >> m_mass; + dcdr >> m_drag_coefficient; + dcdr >> m_center_of_mass; + dcdr >> m_shape; +} + +/*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ +void carla_msgs::msg::CarlaVehicleInfo::id( + uint32_t _id) +{ + m_id = _id; +} + +/*! + * @brief This function returns the value of member id + * @return Value of member id + */ +uint32_t carla_msgs::msg::CarlaVehicleInfo::id() const +{ + return m_id; +} + +/*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ +uint32_t& carla_msgs::msg::CarlaVehicleInfo::id() +{ + return m_id; +} + +/*! + * @brief This function copies the value in member type + * @param _type New value to be copied in member type + */ +void carla_msgs::msg::CarlaVehicleInfo::type( + const std::string& _type) +{ + m_type = _type; +} + +/*! + * @brief This function moves the value in member type + * @param _type New value to be moved in member type + */ +void carla_msgs::msg::CarlaVehicleInfo::type( + std::string&& _type) +{ + m_type = std::move(_type); +} + +/*! + * @brief This function returns a constant reference to member type + * @return Constant reference to member type + */ +const std::string& carla_msgs::msg::CarlaVehicleInfo::type() const +{ + return m_type; +} + +/*! + * @brief This function returns a reference to member type + * @return Reference to member type + */ +std::string& carla_msgs::msg::CarlaVehicleInfo::type() +{ + return m_type; +} +/*! + * @brief This function copies the value in member rolename + * @param _rolename New value to be copied in member rolename + */ +void carla_msgs::msg::CarlaVehicleInfo::rolename( + const std::string& _rolename) +{ + m_rolename = _rolename; +} + +/*! + * @brief This function moves the value in member rolename + * @param _rolename New value to be moved in member rolename + */ +void carla_msgs::msg::CarlaVehicleInfo::rolename( + std::string&& _rolename) +{ + m_rolename = std::move(_rolename); +} + +/*! + * @brief This function returns a constant reference to member rolename + * @return Constant reference to member rolename + */ +const std::string& carla_msgs::msg::CarlaVehicleInfo::rolename() const +{ + return m_rolename; +} + +/*! + * @brief This function returns a reference to member rolename + * @return Reference to member rolename + */ +std::string& carla_msgs::msg::CarlaVehicleInfo::rolename() +{ + return m_rolename; +} +/*! + * @brief This function copies the value in member wheels + * @param _wheels New value to be copied in member wheels + */ +void carla_msgs::msg::CarlaVehicleInfo::wheels( + const std::vector& _wheels) +{ + m_wheels = _wheels; +} + +/*! + * @brief This function moves the value in member wheels + * @param _wheels New value to be moved in member wheels + */ +void carla_msgs::msg::CarlaVehicleInfo::wheels( + std::vector&& _wheels) +{ + m_wheels = std::move(_wheels); +} + +/*! + * @brief This function returns a constant reference to member wheels + * @return Constant reference to member wheels + */ +const std::vector& carla_msgs::msg::CarlaVehicleInfo::wheels() const +{ + return m_wheels; +} + +/*! + * @brief This function returns a reference to member wheels + * @return Reference to member wheels + */ +std::vector& carla_msgs::msg::CarlaVehicleInfo::wheels() +{ + return m_wheels; +} +/*! + * @brief This function sets a value in member max_rpm + * @param _max_rpm New value for member max_rpm + */ +void carla_msgs::msg::CarlaVehicleInfo::max_rpm( + float _max_rpm) +{ + m_max_rpm = _max_rpm; +} + +/*! + * @brief This function returns the value of member max_rpm + * @return Value of member max_rpm + */ +float carla_msgs::msg::CarlaVehicleInfo::max_rpm() const +{ + return m_max_rpm; +} + +/*! + * @brief This function returns a reference to member max_rpm + * @return Reference to member max_rpm + */ +float& carla_msgs::msg::CarlaVehicleInfo::max_rpm() +{ + return m_max_rpm; +} + +/*! + * @brief This function sets a value in member moi + * @param _moi New value for member moi + */ +void carla_msgs::msg::CarlaVehicleInfo::moi( + float _moi) +{ + m_moi = _moi; +} + +/*! + * @brief This function returns the value of member moi + * @return Value of member moi + */ +float carla_msgs::msg::CarlaVehicleInfo::moi() const +{ + return m_moi; +} + +/*! + * @brief This function returns a reference to member moi + * @return Reference to member moi + */ +float& carla_msgs::msg::CarlaVehicleInfo::moi() +{ + return m_moi; +} + +/*! + * @brief This function sets a value in member damping_rate_full_throttle + * @param _damping_rate_full_throttle New value for member damping_rate_full_throttle + */ +void carla_msgs::msg::CarlaVehicleInfo::damping_rate_full_throttle( + float _damping_rate_full_throttle) +{ + m_damping_rate_full_throttle = _damping_rate_full_throttle; +} + +/*! + * @brief This function returns the value of member damping_rate_full_throttle + * @return Value of member damping_rate_full_throttle + */ +float carla_msgs::msg::CarlaVehicleInfo::damping_rate_full_throttle() const +{ + return m_damping_rate_full_throttle; +} + +/*! + * @brief This function returns a reference to member damping_rate_full_throttle + * @return Reference to member damping_rate_full_throttle + */ +float& carla_msgs::msg::CarlaVehicleInfo::damping_rate_full_throttle() +{ + return m_damping_rate_full_throttle; +} + +/*! + * @brief This function sets a value in member damping_rate_zero_throttle_clutch_engaged + * @param _damping_rate_zero_throttle_clutch_engaged New value for member damping_rate_zero_throttle_clutch_engaged + */ +void carla_msgs::msg::CarlaVehicleInfo::damping_rate_zero_throttle_clutch_engaged( + float _damping_rate_zero_throttle_clutch_engaged) +{ + m_damping_rate_zero_throttle_clutch_engaged = _damping_rate_zero_throttle_clutch_engaged; +} + +/*! + * @brief This function returns the value of member damping_rate_zero_throttle_clutch_engaged + * @return Value of member damping_rate_zero_throttle_clutch_engaged + */ +float carla_msgs::msg::CarlaVehicleInfo::damping_rate_zero_throttle_clutch_engaged() const +{ + return m_damping_rate_zero_throttle_clutch_engaged; +} + +/*! + * @brief This function returns a reference to member damping_rate_zero_throttle_clutch_engaged + * @return Reference to member damping_rate_zero_throttle_clutch_engaged + */ +float& carla_msgs::msg::CarlaVehicleInfo::damping_rate_zero_throttle_clutch_engaged() +{ + return m_damping_rate_zero_throttle_clutch_engaged; +} + +/*! + * @brief This function sets a value in member damping_rate_zero_throttle_clutch_disengaged + * @param _damping_rate_zero_throttle_clutch_disengaged New value for member damping_rate_zero_throttle_clutch_disengaged + */ +void carla_msgs::msg::CarlaVehicleInfo::damping_rate_zero_throttle_clutch_disengaged( + float _damping_rate_zero_throttle_clutch_disengaged) +{ + m_damping_rate_zero_throttle_clutch_disengaged = _damping_rate_zero_throttle_clutch_disengaged; +} + +/*! + * @brief This function returns the value of member damping_rate_zero_throttle_clutch_disengaged + * @return Value of member damping_rate_zero_throttle_clutch_disengaged + */ +float carla_msgs::msg::CarlaVehicleInfo::damping_rate_zero_throttle_clutch_disengaged() const +{ + return m_damping_rate_zero_throttle_clutch_disengaged; +} + +/*! + * @brief This function returns a reference to member damping_rate_zero_throttle_clutch_disengaged + * @return Reference to member damping_rate_zero_throttle_clutch_disengaged + */ +float& carla_msgs::msg::CarlaVehicleInfo::damping_rate_zero_throttle_clutch_disengaged() +{ + return m_damping_rate_zero_throttle_clutch_disengaged; +} + +/*! + * @brief This function sets a value in member use_gear_autobox + * @param _use_gear_autobox New value for member use_gear_autobox + */ +void carla_msgs::msg::CarlaVehicleInfo::use_gear_autobox( + bool _use_gear_autobox) +{ + m_use_gear_autobox = _use_gear_autobox; +} + +/*! + * @brief This function returns the value of member use_gear_autobox + * @return Value of member use_gear_autobox + */ +bool carla_msgs::msg::CarlaVehicleInfo::use_gear_autobox() const +{ + return m_use_gear_autobox; +} + +/*! + * @brief This function returns a reference to member use_gear_autobox + * @return Reference to member use_gear_autobox + */ +bool& carla_msgs::msg::CarlaVehicleInfo::use_gear_autobox() +{ + return m_use_gear_autobox; +} + +/*! + * @brief This function sets a value in member gear_switch_time + * @param _gear_switch_time New value for member gear_switch_time + */ +void carla_msgs::msg::CarlaVehicleInfo::gear_switch_time( + float _gear_switch_time) +{ + m_gear_switch_time = _gear_switch_time; +} + +/*! + * @brief This function returns the value of member gear_switch_time + * @return Value of member gear_switch_time + */ +float carla_msgs::msg::CarlaVehicleInfo::gear_switch_time() const +{ + return m_gear_switch_time; +} + +/*! + * @brief This function returns a reference to member gear_switch_time + * @return Reference to member gear_switch_time + */ +float& carla_msgs::msg::CarlaVehicleInfo::gear_switch_time() +{ + return m_gear_switch_time; +} + +/*! + * @brief This function sets a value in member clutch_strength + * @param _clutch_strength New value for member clutch_strength + */ +void carla_msgs::msg::CarlaVehicleInfo::clutch_strength( + float _clutch_strength) +{ + m_clutch_strength = _clutch_strength; +} + +/*! + * @brief This function returns the value of member clutch_strength + * @return Value of member clutch_strength + */ +float carla_msgs::msg::CarlaVehicleInfo::clutch_strength() const +{ + return m_clutch_strength; +} + +/*! + * @brief This function returns a reference to member clutch_strength + * @return Reference to member clutch_strength + */ +float& carla_msgs::msg::CarlaVehicleInfo::clutch_strength() +{ + return m_clutch_strength; +} + +/*! + * @brief This function sets a value in member mass + * @param _mass New value for member mass + */ +void carla_msgs::msg::CarlaVehicleInfo::mass( + float _mass) +{ + m_mass = _mass; +} + +/*! + * @brief This function returns the value of member mass + * @return Value of member mass + */ +float carla_msgs::msg::CarlaVehicleInfo::mass() const +{ + return m_mass; +} + +/*! + * @brief This function returns a reference to member mass + * @return Reference to member mass + */ +float& carla_msgs::msg::CarlaVehicleInfo::mass() +{ + return m_mass; +} + +/*! + * @brief This function sets a value in member drag_coefficient + * @param _drag_coefficient New value for member drag_coefficient + */ +void carla_msgs::msg::CarlaVehicleInfo::drag_coefficient( + float _drag_coefficient) +{ + m_drag_coefficient = _drag_coefficient; +} + +/*! + * @brief This function returns the value of member drag_coefficient + * @return Value of member drag_coefficient + */ +float carla_msgs::msg::CarlaVehicleInfo::drag_coefficient() const +{ + return m_drag_coefficient; +} + +/*! + * @brief This function returns a reference to member drag_coefficient + * @return Reference to member drag_coefficient + */ +float& carla_msgs::msg::CarlaVehicleInfo::drag_coefficient() +{ + return m_drag_coefficient; +} + +/*! + * @brief This function copies the value in member center_of_mass + * @param _center_of_mass New value to be copied in member center_of_mass + */ +void carla_msgs::msg::CarlaVehicleInfo::center_of_mass( + const geometry_msgs::msg::Vector3& _center_of_mass) +{ + m_center_of_mass = _center_of_mass; +} + +/*! + * @brief This function moves the value in member center_of_mass + * @param _center_of_mass New value to be moved in member center_of_mass + */ +void carla_msgs::msg::CarlaVehicleInfo::center_of_mass( + geometry_msgs::msg::Vector3&& _center_of_mass) +{ + m_center_of_mass = std::move(_center_of_mass); +} + +/*! + * @brief This function returns a constant reference to member center_of_mass + * @return Constant reference to member center_of_mass + */ +const geometry_msgs::msg::Vector3& carla_msgs::msg::CarlaVehicleInfo::center_of_mass() const +{ + return m_center_of_mass; +} + +/*! + * @brief This function returns a reference to member center_of_mass + * @return Reference to member center_of_mass + */ +geometry_msgs::msg::Vector3& carla_msgs::msg::CarlaVehicleInfo::center_of_mass() +{ + return m_center_of_mass; +} +/*! + * @brief This function copies the value in member shape + * @param _shape New value to be copied in member shape + */ +void carla_msgs::msg::CarlaVehicleInfo::shape( + const shape_msgs::msg::SolidPrimitive& _shape) +{ + m_shape = _shape; +} + +/*! + * @brief This function moves the value in member shape + * @param _shape New value to be moved in member shape + */ +void carla_msgs::msg::CarlaVehicleInfo::shape( + shape_msgs::msg::SolidPrimitive&& _shape) +{ + m_shape = std::move(_shape); +} + +/*! + * @brief This function returns a constant reference to member shape + * @return Constant reference to member shape + */ +const shape_msgs::msg::SolidPrimitive& carla_msgs::msg::CarlaVehicleInfo::shape() const +{ + return m_shape; +} + +/*! + * @brief This function returns a reference to member shape + * @return Reference to member shape + */ +shape_msgs::msg::SolidPrimitive& carla_msgs::msg::CarlaVehicleInfo::shape() +{ + return m_shape; +} + +size_t carla_msgs::msg::CarlaVehicleInfo::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaVehicleInfo::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaVehicleInfo::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfo.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfo.h new file mode 100644 index 00000000000..bd66fe62807 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfo.h @@ -0,0 +1,542 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleInfo.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLEINFO_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLEINFO_H_ + +#include "CarlaVehicleInfoWheel.h" +#include "shape_msgs/msg/SolidPrimitive.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CarlaVehicleInfo_SOURCE) +#define CarlaVehicleInfo_DllAPI __declspec( dllexport ) +#else +#define CarlaVehicleInfo_DllAPI __declspec( dllimport ) +#endif // CarlaVehicleInfo_SOURCE +#else +#define CarlaVehicleInfo_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CarlaVehicleInfo_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace msg { + /*! + * @brief This class represents the structure CarlaVehicleInfo defined by the user in the IDL file. + * @ingroup CARLAVEHICLEINFO + */ + class CarlaVehicleInfo + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaVehicleInfo(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaVehicleInfo(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleInfo that will be copied. + */ + eProsima_user_DllExport CarlaVehicleInfo( + const CarlaVehicleInfo& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleInfo that will be copied. + */ + eProsima_user_DllExport CarlaVehicleInfo( + CarlaVehicleInfo&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleInfo that will be copied. + */ + eProsima_user_DllExport CarlaVehicleInfo& operator =( + const CarlaVehicleInfo& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleInfo that will be copied. + */ + eProsima_user_DllExport CarlaVehicleInfo& operator =( + CarlaVehicleInfo&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaVehicleInfo object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaVehicleInfo& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaVehicleInfo object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaVehicleInfo& x) const; + + /*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ + eProsima_user_DllExport void id( + uint32_t _id); + + /*! + * @brief This function returns the value of member id + * @return Value of member id + */ + eProsima_user_DllExport uint32_t id() const; + + /*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ + eProsima_user_DllExport uint32_t& id(); + + /*! + * @brief This function copies the value in member type + * @param _type New value to be copied in member type + */ + eProsima_user_DllExport void type( + const std::string& _type); + + /*! + * @brief This function moves the value in member type + * @param _type New value to be moved in member type + */ + eProsima_user_DllExport void type( + std::string&& _type); + + /*! + * @brief This function returns a constant reference to member type + * @return Constant reference to member type + */ + eProsima_user_DllExport const std::string& type() const; + + /*! + * @brief This function returns a reference to member type + * @return Reference to member type + */ + eProsima_user_DllExport std::string& type(); + /*! + * @brief This function copies the value in member rolename + * @param _rolename New value to be copied in member rolename + */ + eProsima_user_DllExport void rolename( + const std::string& _rolename); + + /*! + * @brief This function moves the value in member rolename + * @param _rolename New value to be moved in member rolename + */ + eProsima_user_DllExport void rolename( + std::string&& _rolename); + + /*! + * @brief This function returns a constant reference to member rolename + * @return Constant reference to member rolename + */ + eProsima_user_DllExport const std::string& rolename() const; + + /*! + * @brief This function returns a reference to member rolename + * @return Reference to member rolename + */ + eProsima_user_DllExport std::string& rolename(); + /*! + * @brief This function copies the value in member wheels + * @param _wheels New value to be copied in member wheels + */ + eProsima_user_DllExport void wheels( + const std::vector& _wheels); + + /*! + * @brief This function moves the value in member wheels + * @param _wheels New value to be moved in member wheels + */ + eProsima_user_DllExport void wheels( + std::vector&& _wheels); + + /*! + * @brief This function returns a constant reference to member wheels + * @return Constant reference to member wheels + */ + eProsima_user_DllExport const std::vector& wheels() const; + + /*! + * @brief This function returns a reference to member wheels + * @return Reference to member wheels + */ + eProsima_user_DllExport std::vector& wheels(); + /*! + * @brief This function sets a value in member max_rpm + * @param _max_rpm New value for member max_rpm + */ + eProsima_user_DllExport void max_rpm( + float _max_rpm); + + /*! + * @brief This function returns the value of member max_rpm + * @return Value of member max_rpm + */ + eProsima_user_DllExport float max_rpm() const; + + /*! + * @brief This function returns a reference to member max_rpm + * @return Reference to member max_rpm + */ + eProsima_user_DllExport float& max_rpm(); + + /*! + * @brief This function sets a value in member moi + * @param _moi New value for member moi + */ + eProsima_user_DllExport void moi( + float _moi); + + /*! + * @brief This function returns the value of member moi + * @return Value of member moi + */ + eProsima_user_DllExport float moi() const; + + /*! + * @brief This function returns a reference to member moi + * @return Reference to member moi + */ + eProsima_user_DllExport float& moi(); + + /*! + * @brief This function sets a value in member damping_rate_full_throttle + * @param _damping_rate_full_throttle New value for member damping_rate_full_throttle + */ + eProsima_user_DllExport void damping_rate_full_throttle( + float _damping_rate_full_throttle); + + /*! + * @brief This function returns the value of member damping_rate_full_throttle + * @return Value of member damping_rate_full_throttle + */ + eProsima_user_DllExport float damping_rate_full_throttle() const; + + /*! + * @brief This function returns a reference to member damping_rate_full_throttle + * @return Reference to member damping_rate_full_throttle + */ + eProsima_user_DllExport float& damping_rate_full_throttle(); + + /*! + * @brief This function sets a value in member damping_rate_zero_throttle_clutch_engaged + * @param _damping_rate_zero_throttle_clutch_engaged New value for member damping_rate_zero_throttle_clutch_engaged + */ + eProsima_user_DllExport void damping_rate_zero_throttle_clutch_engaged( + float _damping_rate_zero_throttle_clutch_engaged); + + /*! + * @brief This function returns the value of member damping_rate_zero_throttle_clutch_engaged + * @return Value of member damping_rate_zero_throttle_clutch_engaged + */ + eProsima_user_DllExport float damping_rate_zero_throttle_clutch_engaged() const; + + /*! + * @brief This function returns a reference to member damping_rate_zero_throttle_clutch_engaged + * @return Reference to member damping_rate_zero_throttle_clutch_engaged + */ + eProsima_user_DllExport float& damping_rate_zero_throttle_clutch_engaged(); + + /*! + * @brief This function sets a value in member damping_rate_zero_throttle_clutch_disengaged + * @param _damping_rate_zero_throttle_clutch_disengaged New value for member damping_rate_zero_throttle_clutch_disengaged + */ + eProsima_user_DllExport void damping_rate_zero_throttle_clutch_disengaged( + float _damping_rate_zero_throttle_clutch_disengaged); + + /*! + * @brief This function returns the value of member damping_rate_zero_throttle_clutch_disengaged + * @return Value of member damping_rate_zero_throttle_clutch_disengaged + */ + eProsima_user_DllExport float damping_rate_zero_throttle_clutch_disengaged() const; + + /*! + * @brief This function returns a reference to member damping_rate_zero_throttle_clutch_disengaged + * @return Reference to member damping_rate_zero_throttle_clutch_disengaged + */ + eProsima_user_DllExport float& damping_rate_zero_throttle_clutch_disengaged(); + + /*! + * @brief This function sets a value in member use_gear_autobox + * @param _use_gear_autobox New value for member use_gear_autobox + */ + eProsima_user_DllExport void use_gear_autobox( + bool _use_gear_autobox); + + /*! + * @brief This function returns the value of member use_gear_autobox + * @return Value of member use_gear_autobox + */ + eProsima_user_DllExport bool use_gear_autobox() const; + + /*! + * @brief This function returns a reference to member use_gear_autobox + * @return Reference to member use_gear_autobox + */ + eProsima_user_DllExport bool& use_gear_autobox(); + + /*! + * @brief This function sets a value in member gear_switch_time + * @param _gear_switch_time New value for member gear_switch_time + */ + eProsima_user_DllExport void gear_switch_time( + float _gear_switch_time); + + /*! + * @brief This function returns the value of member gear_switch_time + * @return Value of member gear_switch_time + */ + eProsima_user_DllExport float gear_switch_time() const; + + /*! + * @brief This function returns a reference to member gear_switch_time + * @return Reference to member gear_switch_time + */ + eProsima_user_DllExport float& gear_switch_time(); + + /*! + * @brief This function sets a value in member clutch_strength + * @param _clutch_strength New value for member clutch_strength + */ + eProsima_user_DllExport void clutch_strength( + float _clutch_strength); + + /*! + * @brief This function returns the value of member clutch_strength + * @return Value of member clutch_strength + */ + eProsima_user_DllExport float clutch_strength() const; + + /*! + * @brief This function returns a reference to member clutch_strength + * @return Reference to member clutch_strength + */ + eProsima_user_DllExport float& clutch_strength(); + + /*! + * @brief This function sets a value in member mass + * @param _mass New value for member mass + */ + eProsima_user_DllExport void mass( + float _mass); + + /*! + * @brief This function returns the value of member mass + * @return Value of member mass + */ + eProsima_user_DllExport float mass() const; + + /*! + * @brief This function returns a reference to member mass + * @return Reference to member mass + */ + eProsima_user_DllExport float& mass(); + + /*! + * @brief This function sets a value in member drag_coefficient + * @param _drag_coefficient New value for member drag_coefficient + */ + eProsima_user_DllExport void drag_coefficient( + float _drag_coefficient); + + /*! + * @brief This function returns the value of member drag_coefficient + * @return Value of member drag_coefficient + */ + eProsima_user_DllExport float drag_coefficient() const; + + /*! + * @brief This function returns a reference to member drag_coefficient + * @return Reference to member drag_coefficient + */ + eProsima_user_DllExport float& drag_coefficient(); + + /*! + * @brief This function copies the value in member center_of_mass + * @param _center_of_mass New value to be copied in member center_of_mass + */ + eProsima_user_DllExport void center_of_mass( + const geometry_msgs::msg::Vector3& _center_of_mass); + + /*! + * @brief This function moves the value in member center_of_mass + * @param _center_of_mass New value to be moved in member center_of_mass + */ + eProsima_user_DllExport void center_of_mass( + geometry_msgs::msg::Vector3&& _center_of_mass); + + /*! + * @brief This function returns a constant reference to member center_of_mass + * @return Constant reference to member center_of_mass + */ + eProsima_user_DllExport const geometry_msgs::msg::Vector3& center_of_mass() const; + + /*! + * @brief This function returns a reference to member center_of_mass + * @return Reference to member center_of_mass + */ + eProsima_user_DllExport geometry_msgs::msg::Vector3& center_of_mass(); + /*! + * @brief This function copies the value in member shape + * @param _shape New value to be copied in member shape + */ + eProsima_user_DllExport void shape( + const shape_msgs::msg::SolidPrimitive& _shape); + + /*! + * @brief This function moves the value in member shape + * @param _shape New value to be moved in member shape + */ + eProsima_user_DllExport void shape( + shape_msgs::msg::SolidPrimitive&& _shape); + + /*! + * @brief This function returns a constant reference to member shape + * @return Constant reference to member shape + */ + eProsima_user_DllExport const shape_msgs::msg::SolidPrimitive& shape() const; + + /*! + * @brief This function returns a reference to member shape + * @return Reference to member shape + */ + eProsima_user_DllExport shape_msgs::msg::SolidPrimitive& shape(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::msg::CarlaVehicleInfo& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint32_t m_id; + std::string m_type; + std::string m_rolename; + std::vector m_wheels; + float m_max_rpm; + float m_moi; + float m_damping_rate_full_throttle; + float m_damping_rate_zero_throttle_clutch_engaged; + float m_damping_rate_zero_throttle_clutch_disengaged; + bool m_use_gear_autobox; + float m_gear_switch_time; + float m_clutch_strength; + float m_mass; + float m_drag_coefficient; + geometry_msgs::msg::Vector3 m_center_of_mass; + shape_msgs::msg::SolidPrimitive m_shape; + }; + } // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLEINFO_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfoPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfoPubSubTypes.cxx new file mode 100644 index 00000000000..59ecad69af3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfoPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleInfoPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaVehicleInfoPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaVehicleInfoPubSubType::CarlaVehicleInfoPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaVehicleInfo_"); + auto type_size = CarlaVehicleInfo::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaVehicleInfo::isKeyDefined(); + size_t keyLength = CarlaVehicleInfo::getKeyMaxCdrSerializedSize() > 16 ? + CarlaVehicleInfo::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaVehicleInfoPubSubType::~CarlaVehicleInfoPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaVehicleInfoPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaVehicleInfo* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaVehicleInfoPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaVehicleInfo* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaVehicleInfoPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaVehicleInfoPubSubType::createData() + { + return reinterpret_cast(new CarlaVehicleInfo()); + } + + void CarlaVehicleInfoPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaVehicleInfoPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaVehicleInfo* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaVehicleInfo::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaVehicleInfo::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfoPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfoPubSubTypes.h new file mode 100644 index 00000000000..268c9c65cdf --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfoPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleInfoPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLEINFO_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLEINFO_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaVehicleInfo.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaVehicleInfo is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CarlaVehicleInfo defined by the user in the IDL file. + * @ingroup CARLAVEHICLEINFO + */ + class CarlaVehicleInfoPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaVehicleInfo type; + + eProsima_user_DllExport CarlaVehicleInfoPubSubType(); + + eProsima_user_DllExport virtual ~CarlaVehicleInfoPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLEINFO_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfoWheel.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfoWheel.cxx new file mode 100644 index 00000000000..16c3b7adc7d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfoWheel.cxx @@ -0,0 +1,448 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleInfoWheel.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaVehicleInfoWheel.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaVehicleInfoWheel::CarlaVehicleInfoWheel() +{ + // m_tire_friction com.eprosima.idl.parser.typecode.PrimitiveTypeCode@c88a337 + m_tire_friction = 0.0; + // m_damping_rate com.eprosima.idl.parser.typecode.PrimitiveTypeCode@5d0a1059 + m_damping_rate = 0.0; + // m_max_steer_angle com.eprosima.idl.parser.typecode.PrimitiveTypeCode@485966cc + m_max_steer_angle = 0.0; + // m_radius com.eprosima.idl.parser.typecode.PrimitiveTypeCode@1de76cc7 + m_radius = 0.0; + // m_max_brake_torque com.eprosima.idl.parser.typecode.PrimitiveTypeCode@5a56cdac + m_max_brake_torque = 0.0; + // m_max_handbrake_torque com.eprosima.idl.parser.typecode.PrimitiveTypeCode@7c711375 + m_max_handbrake_torque = 0.0; + // m_position com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@57cf54e1 + + +} + +carla_msgs::msg::CarlaVehicleInfoWheel::~CarlaVehicleInfoWheel() +{ + + + + + + +} + +carla_msgs::msg::CarlaVehicleInfoWheel::CarlaVehicleInfoWheel( + const CarlaVehicleInfoWheel& x) +{ + m_tire_friction = x.m_tire_friction; + m_damping_rate = x.m_damping_rate; + m_max_steer_angle = x.m_max_steer_angle; + m_radius = x.m_radius; + m_max_brake_torque = x.m_max_brake_torque; + m_max_handbrake_torque = x.m_max_handbrake_torque; + m_position = x.m_position; +} + +carla_msgs::msg::CarlaVehicleInfoWheel::CarlaVehicleInfoWheel( + CarlaVehicleInfoWheel&& x) +{ + m_tire_friction = x.m_tire_friction; + m_damping_rate = x.m_damping_rate; + m_max_steer_angle = x.m_max_steer_angle; + m_radius = x.m_radius; + m_max_brake_torque = x.m_max_brake_torque; + m_max_handbrake_torque = x.m_max_handbrake_torque; + m_position = std::move(x.m_position); +} + +carla_msgs::msg::CarlaVehicleInfoWheel& carla_msgs::msg::CarlaVehicleInfoWheel::operator =( + const CarlaVehicleInfoWheel& x) +{ + + m_tire_friction = x.m_tire_friction; + m_damping_rate = x.m_damping_rate; + m_max_steer_angle = x.m_max_steer_angle; + m_radius = x.m_radius; + m_max_brake_torque = x.m_max_brake_torque; + m_max_handbrake_torque = x.m_max_handbrake_torque; + m_position = x.m_position; + + return *this; +} + +carla_msgs::msg::CarlaVehicleInfoWheel& carla_msgs::msg::CarlaVehicleInfoWheel::operator =( + CarlaVehicleInfoWheel&& x) +{ + + m_tire_friction = x.m_tire_friction; + m_damping_rate = x.m_damping_rate; + m_max_steer_angle = x.m_max_steer_angle; + m_radius = x.m_radius; + m_max_brake_torque = x.m_max_brake_torque; + m_max_handbrake_torque = x.m_max_handbrake_torque; + m_position = std::move(x.m_position); + + return *this; +} + +bool carla_msgs::msg::CarlaVehicleInfoWheel::operator ==( + const CarlaVehicleInfoWheel& x) const +{ + + return (m_tire_friction == x.m_tire_friction && m_damping_rate == x.m_damping_rate && m_max_steer_angle == x.m_max_steer_angle && m_radius == x.m_radius && m_max_brake_torque == x.m_max_brake_torque && m_max_handbrake_torque == x.m_max_handbrake_torque && m_position == x.m_position); +} + +bool carla_msgs::msg::CarlaVehicleInfoWheel::operator !=( + const CarlaVehicleInfoWheel& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaVehicleInfoWheel::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += geometry_msgs::msg::Vector3::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaVehicleInfoWheel::getCdrSerializedSize( + const carla_msgs::msg::CarlaVehicleInfoWheel& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += geometry_msgs::msg::Vector3::getCdrSerializedSize(data.position(), current_alignment); + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaVehicleInfoWheel::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_tire_friction; + scdr << m_damping_rate; + scdr << m_max_steer_angle; + scdr << m_radius; + scdr << m_max_brake_torque; + scdr << m_max_handbrake_torque; + scdr << m_position; + +} + +void carla_msgs::msg::CarlaVehicleInfoWheel::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_tire_friction; + dcdr >> m_damping_rate; + dcdr >> m_max_steer_angle; + dcdr >> m_radius; + dcdr >> m_max_brake_torque; + dcdr >> m_max_handbrake_torque; + dcdr >> m_position; +} + +/*! + * @brief This function sets a value in member tire_friction + * @param _tire_friction New value for member tire_friction + */ +void carla_msgs::msg::CarlaVehicleInfoWheel::tire_friction( + float _tire_friction) +{ + m_tire_friction = _tire_friction; +} + +/*! + * @brief This function returns the value of member tire_friction + * @return Value of member tire_friction + */ +float carla_msgs::msg::CarlaVehicleInfoWheel::tire_friction() const +{ + return m_tire_friction; +} + +/*! + * @brief This function returns a reference to member tire_friction + * @return Reference to member tire_friction + */ +float& carla_msgs::msg::CarlaVehicleInfoWheel::tire_friction() +{ + return m_tire_friction; +} + +/*! + * @brief This function sets a value in member damping_rate + * @param _damping_rate New value for member damping_rate + */ +void carla_msgs::msg::CarlaVehicleInfoWheel::damping_rate( + float _damping_rate) +{ + m_damping_rate = _damping_rate; +} + +/*! + * @brief This function returns the value of member damping_rate + * @return Value of member damping_rate + */ +float carla_msgs::msg::CarlaVehicleInfoWheel::damping_rate() const +{ + return m_damping_rate; +} + +/*! + * @brief This function returns a reference to member damping_rate + * @return Reference to member damping_rate + */ +float& carla_msgs::msg::CarlaVehicleInfoWheel::damping_rate() +{ + return m_damping_rate; +} + +/*! + * @brief This function sets a value in member max_steer_angle + * @param _max_steer_angle New value for member max_steer_angle + */ +void carla_msgs::msg::CarlaVehicleInfoWheel::max_steer_angle( + float _max_steer_angle) +{ + m_max_steer_angle = _max_steer_angle; +} + +/*! + * @brief This function returns the value of member max_steer_angle + * @return Value of member max_steer_angle + */ +float carla_msgs::msg::CarlaVehicleInfoWheel::max_steer_angle() const +{ + return m_max_steer_angle; +} + +/*! + * @brief This function returns a reference to member max_steer_angle + * @return Reference to member max_steer_angle + */ +float& carla_msgs::msg::CarlaVehicleInfoWheel::max_steer_angle() +{ + return m_max_steer_angle; +} + +/*! + * @brief This function sets a value in member radius + * @param _radius New value for member radius + */ +void carla_msgs::msg::CarlaVehicleInfoWheel::radius( + float _radius) +{ + m_radius = _radius; +} + +/*! + * @brief This function returns the value of member radius + * @return Value of member radius + */ +float carla_msgs::msg::CarlaVehicleInfoWheel::radius() const +{ + return m_radius; +} + +/*! + * @brief This function returns a reference to member radius + * @return Reference to member radius + */ +float& carla_msgs::msg::CarlaVehicleInfoWheel::radius() +{ + return m_radius; +} + +/*! + * @brief This function sets a value in member max_brake_torque + * @param _max_brake_torque New value for member max_brake_torque + */ +void carla_msgs::msg::CarlaVehicleInfoWheel::max_brake_torque( + float _max_brake_torque) +{ + m_max_brake_torque = _max_brake_torque; +} + +/*! + * @brief This function returns the value of member max_brake_torque + * @return Value of member max_brake_torque + */ +float carla_msgs::msg::CarlaVehicleInfoWheel::max_brake_torque() const +{ + return m_max_brake_torque; +} + +/*! + * @brief This function returns a reference to member max_brake_torque + * @return Reference to member max_brake_torque + */ +float& carla_msgs::msg::CarlaVehicleInfoWheel::max_brake_torque() +{ + return m_max_brake_torque; +} + +/*! + * @brief This function sets a value in member max_handbrake_torque + * @param _max_handbrake_torque New value for member max_handbrake_torque + */ +void carla_msgs::msg::CarlaVehicleInfoWheel::max_handbrake_torque( + float _max_handbrake_torque) +{ + m_max_handbrake_torque = _max_handbrake_torque; +} + +/*! + * @brief This function returns the value of member max_handbrake_torque + * @return Value of member max_handbrake_torque + */ +float carla_msgs::msg::CarlaVehicleInfoWheel::max_handbrake_torque() const +{ + return m_max_handbrake_torque; +} + +/*! + * @brief This function returns a reference to member max_handbrake_torque + * @return Reference to member max_handbrake_torque + */ +float& carla_msgs::msg::CarlaVehicleInfoWheel::max_handbrake_torque() +{ + return m_max_handbrake_torque; +} + +/*! + * @brief This function copies the value in member position + * @param _position New value to be copied in member position + */ +void carla_msgs::msg::CarlaVehicleInfoWheel::position( + const geometry_msgs::msg::Vector3& _position) +{ + m_position = _position; +} + +/*! + * @brief This function moves the value in member position + * @param _position New value to be moved in member position + */ +void carla_msgs::msg::CarlaVehicleInfoWheel::position( + geometry_msgs::msg::Vector3&& _position) +{ + m_position = std::move(_position); +} + +/*! + * @brief This function returns a constant reference to member position + * @return Constant reference to member position + */ +const geometry_msgs::msg::Vector3& carla_msgs::msg::CarlaVehicleInfoWheel::position() const +{ + return m_position; +} + +/*! + * @brief This function returns a reference to member position + * @return Reference to member position + */ +geometry_msgs::msg::Vector3& carla_msgs::msg::CarlaVehicleInfoWheel::position() +{ + return m_position; +} + +size_t carla_msgs::msg::CarlaVehicleInfoWheel::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaVehicleInfoWheel::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaVehicleInfoWheel::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfoWheel.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfoWheel.h new file mode 100644 index 00000000000..4f5875e074d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfoWheel.h @@ -0,0 +1,337 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleInfoWheel.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLEINFOWHEEL_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLEINFOWHEEL_H_ + +#include "geometry_msgs/msg/Vector3.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CarlaVehicleInfoWheel_SOURCE) +#define CarlaVehicleInfoWheel_DllAPI __declspec( dllexport ) +#else +#define CarlaVehicleInfoWheel_DllAPI __declspec( dllimport ) +#endif // CarlaVehicleInfoWheel_SOURCE +#else +#define CarlaVehicleInfoWheel_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CarlaVehicleInfoWheel_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace msg { + /*! + * @brief This class represents the structure CarlaVehicleInfoWheel defined by the user in the IDL file. + * @ingroup CARLAVEHICLEINFOWHEEL + */ + class CarlaVehicleInfoWheel + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaVehicleInfoWheel(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaVehicleInfoWheel(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleInfoWheel that will be copied. + */ + eProsima_user_DllExport CarlaVehicleInfoWheel( + const CarlaVehicleInfoWheel& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleInfoWheel that will be copied. + */ + eProsima_user_DllExport CarlaVehicleInfoWheel( + CarlaVehicleInfoWheel&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleInfoWheel that will be copied. + */ + eProsima_user_DllExport CarlaVehicleInfoWheel& operator =( + const CarlaVehicleInfoWheel& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleInfoWheel that will be copied. + */ + eProsima_user_DllExport CarlaVehicleInfoWheel& operator =( + CarlaVehicleInfoWheel&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaVehicleInfoWheel object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaVehicleInfoWheel& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaVehicleInfoWheel object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaVehicleInfoWheel& x) const; + + /*! + * @brief This function sets a value in member tire_friction + * @param _tire_friction New value for member tire_friction + */ + eProsima_user_DllExport void tire_friction( + float _tire_friction); + + /*! + * @brief This function returns the value of member tire_friction + * @return Value of member tire_friction + */ + eProsima_user_DllExport float tire_friction() const; + + /*! + * @brief This function returns a reference to member tire_friction + * @return Reference to member tire_friction + */ + eProsima_user_DllExport float& tire_friction(); + + /*! + * @brief This function sets a value in member damping_rate + * @param _damping_rate New value for member damping_rate + */ + eProsima_user_DllExport void damping_rate( + float _damping_rate); + + /*! + * @brief This function returns the value of member damping_rate + * @return Value of member damping_rate + */ + eProsima_user_DllExport float damping_rate() const; + + /*! + * @brief This function returns a reference to member damping_rate + * @return Reference to member damping_rate + */ + eProsima_user_DllExport float& damping_rate(); + + /*! + * @brief This function sets a value in member max_steer_angle + * @param _max_steer_angle New value for member max_steer_angle + */ + eProsima_user_DllExport void max_steer_angle( + float _max_steer_angle); + + /*! + * @brief This function returns the value of member max_steer_angle + * @return Value of member max_steer_angle + */ + eProsima_user_DllExport float max_steer_angle() const; + + /*! + * @brief This function returns a reference to member max_steer_angle + * @return Reference to member max_steer_angle + */ + eProsima_user_DllExport float& max_steer_angle(); + + /*! + * @brief This function sets a value in member radius + * @param _radius New value for member radius + */ + eProsima_user_DllExport void radius( + float _radius); + + /*! + * @brief This function returns the value of member radius + * @return Value of member radius + */ + eProsima_user_DllExport float radius() const; + + /*! + * @brief This function returns a reference to member radius + * @return Reference to member radius + */ + eProsima_user_DllExport float& radius(); + + /*! + * @brief This function sets a value in member max_brake_torque + * @param _max_brake_torque New value for member max_brake_torque + */ + eProsima_user_DllExport void max_brake_torque( + float _max_brake_torque); + + /*! + * @brief This function returns the value of member max_brake_torque + * @return Value of member max_brake_torque + */ + eProsima_user_DllExport float max_brake_torque() const; + + /*! + * @brief This function returns a reference to member max_brake_torque + * @return Reference to member max_brake_torque + */ + eProsima_user_DllExport float& max_brake_torque(); + + /*! + * @brief This function sets a value in member max_handbrake_torque + * @param _max_handbrake_torque New value for member max_handbrake_torque + */ + eProsima_user_DllExport void max_handbrake_torque( + float _max_handbrake_torque); + + /*! + * @brief This function returns the value of member max_handbrake_torque + * @return Value of member max_handbrake_torque + */ + eProsima_user_DllExport float max_handbrake_torque() const; + + /*! + * @brief This function returns a reference to member max_handbrake_torque + * @return Reference to member max_handbrake_torque + */ + eProsima_user_DllExport float& max_handbrake_torque(); + + /*! + * @brief This function copies the value in member position + * @param _position New value to be copied in member position + */ + eProsima_user_DllExport void position( + const geometry_msgs::msg::Vector3& _position); + + /*! + * @brief This function moves the value in member position + * @param _position New value to be moved in member position + */ + eProsima_user_DllExport void position( + geometry_msgs::msg::Vector3&& _position); + + /*! + * @brief This function returns a constant reference to member position + * @return Constant reference to member position + */ + eProsima_user_DllExport const geometry_msgs::msg::Vector3& position() const; + + /*! + * @brief This function returns a reference to member position + * @return Reference to member position + */ + eProsima_user_DllExport geometry_msgs::msg::Vector3& position(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::msg::CarlaVehicleInfoWheel& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + float m_tire_friction; + float m_damping_rate; + float m_max_steer_angle; + float m_radius; + float m_max_brake_torque; + float m_max_handbrake_torque; + geometry_msgs::msg::Vector3 m_position; + }; + } // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLEINFOWHEEL_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfoWheelPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfoWheelPubSubTypes.cxx new file mode 100644 index 00000000000..a6f26a41673 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfoWheelPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleInfoWheelPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaVehicleInfoWheelPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaVehicleInfoWheelPubSubType::CarlaVehicleInfoWheelPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaVehicleInfoWheel_"); + auto type_size = CarlaVehicleInfoWheel::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaVehicleInfoWheel::isKeyDefined(); + size_t keyLength = CarlaVehicleInfoWheel::getKeyMaxCdrSerializedSize() > 16 ? + CarlaVehicleInfoWheel::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaVehicleInfoWheelPubSubType::~CarlaVehicleInfoWheelPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaVehicleInfoWheelPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaVehicleInfoWheel* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaVehicleInfoWheelPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaVehicleInfoWheel* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaVehicleInfoWheelPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaVehicleInfoWheelPubSubType::createData() + { + return reinterpret_cast(new CarlaVehicleInfoWheel()); + } + + void CarlaVehicleInfoWheelPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaVehicleInfoWheelPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaVehicleInfoWheel* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaVehicleInfoWheel::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaVehicleInfoWheel::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfoWheelPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfoWheelPubSubTypes.h new file mode 100644 index 00000000000..96396371bef --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleInfoWheelPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleInfoWheelPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLEINFOWHEEL_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLEINFOWHEEL_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaVehicleInfoWheel.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaVehicleInfoWheel is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CarlaVehicleInfoWheel defined by the user in the IDL file. + * @ingroup CARLAVEHICLEINFOWHEEL + */ + class CarlaVehicleInfoWheelPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaVehicleInfoWheel type; + + eProsima_user_DllExport CarlaVehicleInfoWheelPubSubType(); + + eProsima_user_DllExport virtual ~CarlaVehicleInfoWheelPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) CarlaVehicleInfoWheel(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLEINFOWHEEL_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryData.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryData.cxx new file mode 100644 index 00000000000..be85da305b6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryData.cxx @@ -0,0 +1,551 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleTelemetryData.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaVehicleTelemetryData.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaVehicleTelemetryData::CarlaVehicleTelemetryData() +{ + // m_header com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@7dc0f706 + + // m_speed com.eprosima.idl.parser.typecode.PrimitiveTypeCode@4009e306 + m_speed = 0.0; + // m_steer com.eprosima.idl.parser.typecode.PrimitiveTypeCode@43c1b556 + m_steer = 0.0; + // m_throttle com.eprosima.idl.parser.typecode.PrimitiveTypeCode@587e5365 + m_throttle = 0.0; + // m_brake com.eprosima.idl.parser.typecode.PrimitiveTypeCode@22fcf7ab + m_brake = 0.0; + // m_engine_rpm com.eprosima.idl.parser.typecode.PrimitiveTypeCode@2de23121 + m_engine_rpm = 0.0; + // m_gear com.eprosima.idl.parser.typecode.PrimitiveTypeCode@63475ace + m_gear = 0; + // m_drag com.eprosima.idl.parser.typecode.PrimitiveTypeCode@305b7c14 + m_drag = 0.0; + // m_wheels com.eprosima.idl.parser.typecode.SequenceTypeCode@6913c1fb + + +} + +carla_msgs::msg::CarlaVehicleTelemetryData::~CarlaVehicleTelemetryData() +{ + + + + + + + + +} + +carla_msgs::msg::CarlaVehicleTelemetryData::CarlaVehicleTelemetryData( + const CarlaVehicleTelemetryData& x) +{ + m_header = x.m_header; + m_speed = x.m_speed; + m_steer = x.m_steer; + m_throttle = x.m_throttle; + m_brake = x.m_brake; + m_engine_rpm = x.m_engine_rpm; + m_gear = x.m_gear; + m_drag = x.m_drag; + m_wheels = x.m_wheels; +} + +carla_msgs::msg::CarlaVehicleTelemetryData::CarlaVehicleTelemetryData( + CarlaVehicleTelemetryData&& x) +{ + m_header = std::move(x.m_header); + m_speed = x.m_speed; + m_steer = x.m_steer; + m_throttle = x.m_throttle; + m_brake = x.m_brake; + m_engine_rpm = x.m_engine_rpm; + m_gear = x.m_gear; + m_drag = x.m_drag; + m_wheels = std::move(x.m_wheels); +} + +carla_msgs::msg::CarlaVehicleTelemetryData& carla_msgs::msg::CarlaVehicleTelemetryData::operator =( + const CarlaVehicleTelemetryData& x) +{ + + m_header = x.m_header; + m_speed = x.m_speed; + m_steer = x.m_steer; + m_throttle = x.m_throttle; + m_brake = x.m_brake; + m_engine_rpm = x.m_engine_rpm; + m_gear = x.m_gear; + m_drag = x.m_drag; + m_wheels = x.m_wheels; + + return *this; +} + +carla_msgs::msg::CarlaVehicleTelemetryData& carla_msgs::msg::CarlaVehicleTelemetryData::operator =( + CarlaVehicleTelemetryData&& x) +{ + + m_header = std::move(x.m_header); + m_speed = x.m_speed; + m_steer = x.m_steer; + m_throttle = x.m_throttle; + m_brake = x.m_brake; + m_engine_rpm = x.m_engine_rpm; + m_gear = x.m_gear; + m_drag = x.m_drag; + m_wheels = std::move(x.m_wheels); + + return *this; +} + +bool carla_msgs::msg::CarlaVehicleTelemetryData::operator ==( + const CarlaVehicleTelemetryData& x) const +{ + + return (m_header == x.m_header && m_speed == x.m_speed && m_steer == x.m_steer && m_throttle == x.m_throttle && m_brake == x.m_brake && m_engine_rpm == x.m_engine_rpm && m_gear == x.m_gear && m_drag == x.m_drag && m_wheels == x.m_wheels); +} + +bool carla_msgs::msg::CarlaVehicleTelemetryData::operator !=( + const CarlaVehicleTelemetryData& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaVehicleTelemetryData::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getMaxCdrSerializedSize(current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < 100; ++a) + { + current_alignment += carla_msgs::msg::CarlaVehicleTelemetryDataWheel::getMaxCdrSerializedSize(current_alignment);} + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaVehicleTelemetryData::getCdrSerializedSize( + const carla_msgs::msg::CarlaVehicleTelemetryData& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getCdrSerializedSize(data.header(), current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < data.wheels().size(); ++a) + { + current_alignment += carla_msgs::msg::CarlaVehicleTelemetryDataWheel::getCdrSerializedSize(data.wheels().at(a), current_alignment);} + + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaVehicleTelemetryData::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_header; + scdr << m_speed; + scdr << m_steer; + scdr << m_throttle; + scdr << m_brake; + scdr << m_engine_rpm; + scdr << m_gear; + scdr << m_drag; + scdr << m_wheels; + +} + +void carla_msgs::msg::CarlaVehicleTelemetryData::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_header; + dcdr >> m_speed; + dcdr >> m_steer; + dcdr >> m_throttle; + dcdr >> m_brake; + dcdr >> m_engine_rpm; + dcdr >> m_gear; + dcdr >> m_drag; + dcdr >> m_wheels; +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void carla_msgs::msg::CarlaVehicleTelemetryData::header( + const std_msgs::msg::Header& _header) +{ + m_header = _header; +} + +/*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ +void carla_msgs::msg::CarlaVehicleTelemetryData::header( + std_msgs::msg::Header&& _header) +{ + m_header = std::move(_header); +} + +/*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ +const std_msgs::msg::Header& carla_msgs::msg::CarlaVehicleTelemetryData::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& carla_msgs::msg::CarlaVehicleTelemetryData::header() +{ + return m_header; +} +/*! + * @brief This function sets a value in member speed + * @param _speed New value for member speed + */ +void carla_msgs::msg::CarlaVehicleTelemetryData::speed( + float _speed) +{ + m_speed = _speed; +} + +/*! + * @brief This function returns the value of member speed + * @return Value of member speed + */ +float carla_msgs::msg::CarlaVehicleTelemetryData::speed() const +{ + return m_speed; +} + +/*! + * @brief This function returns a reference to member speed + * @return Reference to member speed + */ +float& carla_msgs::msg::CarlaVehicleTelemetryData::speed() +{ + return m_speed; +} + +/*! + * @brief This function sets a value in member steer + * @param _steer New value for member steer + */ +void carla_msgs::msg::CarlaVehicleTelemetryData::steer( + float _steer) +{ + m_steer = _steer; +} + +/*! + * @brief This function returns the value of member steer + * @return Value of member steer + */ +float carla_msgs::msg::CarlaVehicleTelemetryData::steer() const +{ + return m_steer; +} + +/*! + * @brief This function returns a reference to member steer + * @return Reference to member steer + */ +float& carla_msgs::msg::CarlaVehicleTelemetryData::steer() +{ + return m_steer; +} + +/*! + * @brief This function sets a value in member throttle + * @param _throttle New value for member throttle + */ +void carla_msgs::msg::CarlaVehicleTelemetryData::throttle( + float _throttle) +{ + m_throttle = _throttle; +} + +/*! + * @brief This function returns the value of member throttle + * @return Value of member throttle + */ +float carla_msgs::msg::CarlaVehicleTelemetryData::throttle() const +{ + return m_throttle; +} + +/*! + * @brief This function returns a reference to member throttle + * @return Reference to member throttle + */ +float& carla_msgs::msg::CarlaVehicleTelemetryData::throttle() +{ + return m_throttle; +} + +/*! + * @brief This function sets a value in member brake + * @param _brake New value for member brake + */ +void carla_msgs::msg::CarlaVehicleTelemetryData::brake( + float _brake) +{ + m_brake = _brake; +} + +/*! + * @brief This function returns the value of member brake + * @return Value of member brake + */ +float carla_msgs::msg::CarlaVehicleTelemetryData::brake() const +{ + return m_brake; +} + +/*! + * @brief This function returns a reference to member brake + * @return Reference to member brake + */ +float& carla_msgs::msg::CarlaVehicleTelemetryData::brake() +{ + return m_brake; +} + +/*! + * @brief This function sets a value in member engine_rpm + * @param _engine_rpm New value for member engine_rpm + */ +void carla_msgs::msg::CarlaVehicleTelemetryData::engine_rpm( + float _engine_rpm) +{ + m_engine_rpm = _engine_rpm; +} + +/*! + * @brief This function returns the value of member engine_rpm + * @return Value of member engine_rpm + */ +float carla_msgs::msg::CarlaVehicleTelemetryData::engine_rpm() const +{ + return m_engine_rpm; +} + +/*! + * @brief This function returns a reference to member engine_rpm + * @return Reference to member engine_rpm + */ +float& carla_msgs::msg::CarlaVehicleTelemetryData::engine_rpm() +{ + return m_engine_rpm; +} + +/*! + * @brief This function sets a value in member gear + * @param _gear New value for member gear + */ +void carla_msgs::msg::CarlaVehicleTelemetryData::gear( + int32_t _gear) +{ + m_gear = _gear; +} + +/*! + * @brief This function returns the value of member gear + * @return Value of member gear + */ +int32_t carla_msgs::msg::CarlaVehicleTelemetryData::gear() const +{ + return m_gear; +} + +/*! + * @brief This function returns a reference to member gear + * @return Reference to member gear + */ +int32_t& carla_msgs::msg::CarlaVehicleTelemetryData::gear() +{ + return m_gear; +} + +/*! + * @brief This function sets a value in member drag + * @param _drag New value for member drag + */ +void carla_msgs::msg::CarlaVehicleTelemetryData::drag( + float _drag) +{ + m_drag = _drag; +} + +/*! + * @brief This function returns the value of member drag + * @return Value of member drag + */ +float carla_msgs::msg::CarlaVehicleTelemetryData::drag() const +{ + return m_drag; +} + +/*! + * @brief This function returns a reference to member drag + * @return Reference to member drag + */ +float& carla_msgs::msg::CarlaVehicleTelemetryData::drag() +{ + return m_drag; +} + +/*! + * @brief This function copies the value in member wheels + * @param _wheels New value to be copied in member wheels + */ +void carla_msgs::msg::CarlaVehicleTelemetryData::wheels( + const std::vector& _wheels) +{ + m_wheels = _wheels; +} + +/*! + * @brief This function moves the value in member wheels + * @param _wheels New value to be moved in member wheels + */ +void carla_msgs::msg::CarlaVehicleTelemetryData::wheels( + std::vector&& _wheels) +{ + m_wheels = std::move(_wheels); +} + +/*! + * @brief This function returns a constant reference to member wheels + * @return Constant reference to member wheels + */ +const std::vector& carla_msgs::msg::CarlaVehicleTelemetryData::wheels() const +{ + return m_wheels; +} + +/*! + * @brief This function returns a reference to member wheels + * @return Reference to member wheels + */ +std::vector& carla_msgs::msg::CarlaVehicleTelemetryData::wheels() +{ + return m_wheels; +} + +size_t carla_msgs::msg::CarlaVehicleTelemetryData::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaVehicleTelemetryData::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaVehicleTelemetryData::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/types/PointCloud2.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryData.h similarity index 50% rename from LibCarla/source/carla/ros2/types/PointCloud2.h rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryData.h index 8a4734a917b..fabbe082a68 100644 --- a/LibCarla/source/carla/ros2/types/PointCloud2.h +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryData.h @@ -13,19 +13,17 @@ // limitations under the License. /*! - * @file PointCloud2.h + * @file CarlaVehicleTelemetryData.h * This header file contains the declaration of the described types in the IDL file. * * This file was generated by the tool gen. */ -#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2_H_ -#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2_H_ +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLETELEMETRYDATA_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLETELEMETRYDATA_H_ -#include "Header.h" -#include "PointField.h" - -#include +#include "std_msgs/msg/Header.h" +#include "CarlaVehicleTelemetryDataWheel.h" #include #include @@ -46,16 +44,16 @@ #if defined(_WIN32) #if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(PointCloud2_SOURCE) -#define PointCloud2_DllAPI __declspec( dllexport ) +#if defined(CarlaVehicleTelemetryData_SOURCE) +#define CarlaVehicleTelemetryData_DllAPI __declspec( dllexport ) #else -#define PointCloud2_DllAPI __declspec( dllimport ) -#endif // PointCloud2_SOURCE +#define CarlaVehicleTelemetryData_DllAPI __declspec( dllimport ) +#endif // CarlaVehicleTelemetryData_SOURCE #else -#define PointCloud2_DllAPI +#define CarlaVehicleTelemetryData_DllAPI #endif // EPROSIMA_USER_DLL_EXPORT #else -#define PointCloud2_DllAPI +#define CarlaVehicleTelemetryData_DllAPI #endif // _WIN32 namespace eprosima { @@ -64,67 +62,68 @@ class Cdr; } // namespace fastcdr } // namespace eprosima -namespace sensor_msgs { + +namespace carla_msgs { namespace msg { /*! - * @brief This class represents the structure PointCloud2 defined by the user in the IDL file. - * @ingroup POINTCLOUD2 + * @brief This class represents the structure CarlaVehicleTelemetryData defined by the user in the IDL file. + * @ingroup CARLAVEHICLETELEMETRYDATA */ - class PointCloud2 + class CarlaVehicleTelemetryData { public: /*! * @brief Default constructor. */ - eProsima_user_DllExport PointCloud2(); + eProsima_user_DllExport CarlaVehicleTelemetryData(); /*! * @brief Default destructor. */ - eProsima_user_DllExport ~PointCloud2(); + eProsima_user_DllExport ~CarlaVehicleTelemetryData(); /*! * @brief Copy constructor. - * @param x Reference to the object sensor_msgs::msg::PointCloud2 that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleTelemetryData that will be copied. */ - eProsima_user_DllExport PointCloud2( - const PointCloud2& x); + eProsima_user_DllExport CarlaVehicleTelemetryData( + const CarlaVehicleTelemetryData& x); /*! * @brief Move constructor. - * @param x Reference to the object sensor_msgs::msg::PointCloud2 that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleTelemetryData that will be copied. */ - eProsima_user_DllExport PointCloud2( - PointCloud2&& x) noexcept; + eProsima_user_DllExport CarlaVehicleTelemetryData( + CarlaVehicleTelemetryData&& x); /*! * @brief Copy assignment. - * @param x Reference to the object sensor_msgs::msg::PointCloud2 that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleTelemetryData that will be copied. */ - eProsima_user_DllExport PointCloud2& operator =( - const PointCloud2& x); + eProsima_user_DllExport CarlaVehicleTelemetryData& operator =( + const CarlaVehicleTelemetryData& x); /*! * @brief Move assignment. - * @param x Reference to the object sensor_msgs::msg::PointCloud2 that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleTelemetryData that will be copied. */ - eProsima_user_DllExport PointCloud2& operator =( - PointCloud2&& x) noexcept; + eProsima_user_DllExport CarlaVehicleTelemetryData& operator =( + CarlaVehicleTelemetryData&& x); /*! * @brief Comparison operator. - * @param x sensor_msgs::msg::PointCloud2 object to compare. + * @param x carla_msgs::msg::CarlaVehicleTelemetryData object to compare. */ eProsima_user_DllExport bool operator ==( - const PointCloud2& x) const; + const CarlaVehicleTelemetryData& x) const; /*! * @brief Comparison operator. - * @param x sensor_msgs::msg::PointCloud2 object to compare. + * @param x carla_msgs::msg::CarlaVehicleTelemetryData object to compare. */ eProsima_user_DllExport bool operator !=( - const PointCloud2& x) const; + const CarlaVehicleTelemetryData& x) const; /*! * @brief This function copies the value in member header @@ -152,175 +151,170 @@ namespace sensor_msgs { */ eProsima_user_DllExport std_msgs::msg::Header& header(); /*! - * @brief This function sets a value in member height - * @param _height New value for member height + * @brief This function sets a value in member speed + * @param _speed New value for member speed */ - eProsima_user_DllExport void height( - uint32_t _height); + eProsima_user_DllExport void speed( + float _speed); /*! - * @brief This function returns the value of member height - * @return Value of member height + * @brief This function returns the value of member speed + * @return Value of member speed */ - eProsima_user_DllExport uint32_t height() const; + eProsima_user_DllExport float speed() const; /*! - * @brief This function returns a reference to member height - * @return Reference to member height + * @brief This function returns a reference to member speed + * @return Reference to member speed */ - eProsima_user_DllExport uint32_t& height(); + eProsima_user_DllExport float& speed(); /*! - * @brief This function sets a value in member width - * @param _width New value for member width + * @brief This function sets a value in member steer + * @param _steer New value for member steer */ - eProsima_user_DllExport void width( - uint32_t _width); + eProsima_user_DllExport void steer( + float _steer); /*! - * @brief This function returns the value of member width - * @return Value of member width + * @brief This function returns the value of member steer + * @return Value of member steer */ - eProsima_user_DllExport uint32_t width() const; + eProsima_user_DllExport float steer() const; /*! - * @brief This function returns a reference to member width - * @return Reference to member width + * @brief This function returns a reference to member steer + * @return Reference to member steer */ - eProsima_user_DllExport uint32_t& width(); + eProsima_user_DllExport float& steer(); /*! - * @brief This function copies the value in member fields - * @param _fields New value to be copied in member fields + * @brief This function sets a value in member throttle + * @param _throttle New value for member throttle */ - eProsima_user_DllExport void fields( - const std::vector& _fields); + eProsima_user_DllExport void throttle( + float _throttle); /*! - * @brief This function moves the value in member fields - * @param _fields New value to be moved in member fields + * @brief This function returns the value of member throttle + * @return Value of member throttle */ - eProsima_user_DllExport void fields( - std::vector&& _fields); + eProsima_user_DllExport float throttle() const; /*! - * @brief This function returns a constant reference to member fields - * @return Constant reference to member fields + * @brief This function returns a reference to member throttle + * @return Reference to member throttle */ - eProsima_user_DllExport const std::vector& fields() const; + eProsima_user_DllExport float& throttle(); /*! - * @brief This function returns a reference to member fields - * @return Reference to member fields - */ - eProsima_user_DllExport std::vector& fields(); - /*! - * @brief This function sets a value in member is_bigendian - * @param _is_bigendian New value for member is_bigendian + * @brief This function sets a value in member brake + * @param _brake New value for member brake */ - eProsima_user_DllExport void is_bigendian( - bool _is_bigendian); + eProsima_user_DllExport void brake( + float _brake); /*! - * @brief This function returns the value of member is_bigendian - * @return Value of member is_bigendian + * @brief This function returns the value of member brake + * @return Value of member brake */ - eProsima_user_DllExport bool is_bigendian() const; + eProsima_user_DllExport float brake() const; /*! - * @brief This function returns a reference to member is_bigendian - * @return Reference to member is_bigendian + * @brief This function returns a reference to member brake + * @return Reference to member brake */ - eProsima_user_DllExport bool& is_bigendian(); + eProsima_user_DllExport float& brake(); /*! - * @brief This function sets a value in member point_step - * @param _point_step New value for member point_step + * @brief This function sets a value in member engine_rpm + * @param _engine_rpm New value for member engine_rpm */ - eProsima_user_DllExport void point_step( - uint32_t _point_step); + eProsima_user_DllExport void engine_rpm( + float _engine_rpm); /*! - * @brief This function returns the value of member point_step - * @return Value of member point_step + * @brief This function returns the value of member engine_rpm + * @return Value of member engine_rpm */ - eProsima_user_DllExport uint32_t point_step() const; + eProsima_user_DllExport float engine_rpm() const; /*! - * @brief This function returns a reference to member point_step - * @return Reference to member point_step + * @brief This function returns a reference to member engine_rpm + * @return Reference to member engine_rpm */ - eProsima_user_DllExport uint32_t& point_step(); + eProsima_user_DllExport float& engine_rpm(); /*! - * @brief This function sets a value in member row_step - * @param _row_step New value for member row_step + * @brief This function sets a value in member gear + * @param _gear New value for member gear */ - eProsima_user_DllExport void row_step( - uint32_t _row_step); + eProsima_user_DllExport void gear( + int32_t _gear); /*! - * @brief This function returns the value of member row_step - * @return Value of member row_step + * @brief This function returns the value of member gear + * @return Value of member gear */ - eProsima_user_DllExport uint32_t row_step() const; + eProsima_user_DllExport int32_t gear() const; /*! - * @brief This function returns a reference to member row_step - * @return Reference to member row_step + * @brief This function returns a reference to member gear + * @return Reference to member gear */ - eProsima_user_DllExport uint32_t& row_step(); + eProsima_user_DllExport int32_t& gear(); /*! - * @brief This function copies the value in member data - * @param _data New value to be copied in member data + * @brief This function sets a value in member drag + * @param _drag New value for member drag */ - eProsima_user_DllExport void data( - const std::vector& _data); + eProsima_user_DllExport void drag( + float _drag); /*! - * @brief This function moves the value in member data - * @param _data New value to be moved in member data + * @brief This function returns the value of member drag + * @return Value of member drag */ - eProsima_user_DllExport void data( - std::vector&& _data); + eProsima_user_DllExport float drag() const; /*! - * @brief This function returns a constant reference to member data - * @return Constant reference to member data + * @brief This function returns a reference to member drag + * @return Reference to member drag */ - eProsima_user_DllExport const std::vector& data() const; + eProsima_user_DllExport float& drag(); /*! - * @brief This function returns a reference to member data - * @return Reference to member data + * @brief This function copies the value in member wheels + * @param _wheels New value to be copied in member wheels */ - eProsima_user_DllExport std::vector& data(); + eProsima_user_DllExport void wheels( + const std::vector& _wheels); + /*! - * @brief This function sets a value in member is_dense - * @param _is_dense New value for member is_dense + * @brief This function moves the value in member wheels + * @param _wheels New value to be moved in member wheels */ - eProsima_user_DllExport void is_dense( - bool _is_dense); + eProsima_user_DllExport void wheels( + std::vector&& _wheels); /*! - * @brief This function returns the value of member is_dense - * @return Value of member is_dense + * @brief This function returns a constant reference to member wheels + * @return Constant reference to member wheels */ - eProsima_user_DllExport bool is_dense() const; + eProsima_user_DllExport const std::vector& wheels() const; /*! - * @brief This function returns a reference to member is_dense - * @return Reference to member is_dense + * @brief This function returns a reference to member wheels + * @return Reference to member wheels */ - eProsima_user_DllExport bool& is_dense(); + eProsima_user_DllExport std::vector& wheels(); /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -331,9 +325,10 @@ namespace sensor_msgs { * @return Serialized size. */ eProsima_user_DllExport static size_t getCdrSerializedSize( - const sensor_msgs::msg::PointCloud2& data, + const carla_msgs::msg::CarlaVehicleTelemetryData& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -348,6 +343,8 @@ namespace sensor_msgs { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -370,17 +367,18 @@ namespace sensor_msgs { eprosima::fastcdr::Cdr& cdr) const; private: + std_msgs::msg::Header m_header; - uint32_t m_height; - uint32_t m_width; - std::vector m_fields; - bool m_is_bigendian; - uint32_t m_point_step; - uint32_t m_row_step; - std::vector m_data; - bool m_is_dense; + float m_speed; + float m_steer; + float m_throttle; + float m_brake; + float m_engine_rpm; + int32_t m_gear; + float m_drag; + std::vector m_wheels; }; } // namespace msg -} // namespace sensor_msgs +} // namespace carla_msgs -#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2_H_ +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLETELEMETRYDATA_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryDataPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryDataPubSubTypes.cxx new file mode 100644 index 00000000000..f2ee9edf083 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryDataPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleTelemetryDataPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaVehicleTelemetryDataPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaVehicleTelemetryDataPubSubType::CarlaVehicleTelemetryDataPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaVehicleTelemetryData_"); + auto type_size = CarlaVehicleTelemetryData::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaVehicleTelemetryData::isKeyDefined(); + size_t keyLength = CarlaVehicleTelemetryData::getKeyMaxCdrSerializedSize() > 16 ? + CarlaVehicleTelemetryData::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaVehicleTelemetryDataPubSubType::~CarlaVehicleTelemetryDataPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaVehicleTelemetryDataPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaVehicleTelemetryData* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaVehicleTelemetryDataPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaVehicleTelemetryData* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaVehicleTelemetryDataPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaVehicleTelemetryDataPubSubType::createData() + { + return reinterpret_cast(new CarlaVehicleTelemetryData()); + } + + void CarlaVehicleTelemetryDataPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaVehicleTelemetryDataPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaVehicleTelemetryData* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaVehicleTelemetryData::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaVehicleTelemetryData::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryDataPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryDataPubSubTypes.h new file mode 100644 index 00000000000..26e8587dda3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryDataPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleTelemetryDataPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLETELEMETRYDATA_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLETELEMETRYDATA_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaVehicleTelemetryData.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaVehicleTelemetryData is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CarlaVehicleTelemetryData defined by the user in the IDL file. + * @ingroup CARLAVEHICLETELEMETRYDATA + */ + class CarlaVehicleTelemetryDataPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaVehicleTelemetryData type; + + eProsima_user_DllExport CarlaVehicleTelemetryDataPubSubType(); + + eProsima_user_DllExport virtual ~CarlaVehicleTelemetryDataPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLETELEMETRYDATA_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryDataWheel.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryDataWheel.cxx new file mode 100644 index 00000000000..b9f6dd1df52 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryDataWheel.cxx @@ -0,0 +1,615 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleTelemetryDataWheel.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaVehicleTelemetryDataWheel.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaVehicleTelemetryDataWheel::CarlaVehicleTelemetryDataWheel() +{ + // m_tire_friction com.eprosima.idl.parser.typecode.PrimitiveTypeCode@3c0be339 + m_tire_friction = 0.0; + // m_lat_slip com.eprosima.idl.parser.typecode.PrimitiveTypeCode@15ca7889 + m_lat_slip = 0.0; + // m_long_slip com.eprosima.idl.parser.typecode.PrimitiveTypeCode@6e509ffa + m_long_slip = 0.0; + // m_omega com.eprosima.idl.parser.typecode.PrimitiveTypeCode@2898ac89 + m_omega = 0.0; + // m_tire_load com.eprosima.idl.parser.typecode.PrimitiveTypeCode@683dbc2c + m_tire_load = 0.0; + // m_normalized_tire_load com.eprosima.idl.parser.typecode.PrimitiveTypeCode@68267da0 + m_normalized_tire_load = 0.0; + // m_torque com.eprosima.idl.parser.typecode.PrimitiveTypeCode@2638011 + m_torque = 0.0; + // m_long_force com.eprosima.idl.parser.typecode.PrimitiveTypeCode@6ff29830 + m_long_force = 0.0; + // m_lat_force com.eprosima.idl.parser.typecode.PrimitiveTypeCode@6a2b953e + m_lat_force = 0.0; + // m_normalized_long_force com.eprosima.idl.parser.typecode.PrimitiveTypeCode@a1cdc6d + m_normalized_long_force = 0.0; + // m_normalized_lat_force com.eprosima.idl.parser.typecode.PrimitiveTypeCode@175b9425 + m_normalized_lat_force = 0.0; + +} + +carla_msgs::msg::CarlaVehicleTelemetryDataWheel::~CarlaVehicleTelemetryDataWheel() +{ + + + + + + + + + + +} + +carla_msgs::msg::CarlaVehicleTelemetryDataWheel::CarlaVehicleTelemetryDataWheel( + const CarlaVehicleTelemetryDataWheel& x) +{ + m_tire_friction = x.m_tire_friction; + m_lat_slip = x.m_lat_slip; + m_long_slip = x.m_long_slip; + m_omega = x.m_omega; + m_tire_load = x.m_tire_load; + m_normalized_tire_load = x.m_normalized_tire_load; + m_torque = x.m_torque; + m_long_force = x.m_long_force; + m_lat_force = x.m_lat_force; + m_normalized_long_force = x.m_normalized_long_force; + m_normalized_lat_force = x.m_normalized_lat_force; +} + +carla_msgs::msg::CarlaVehicleTelemetryDataWheel::CarlaVehicleTelemetryDataWheel( + CarlaVehicleTelemetryDataWheel&& x) +{ + m_tire_friction = x.m_tire_friction; + m_lat_slip = x.m_lat_slip; + m_long_slip = x.m_long_slip; + m_omega = x.m_omega; + m_tire_load = x.m_tire_load; + m_normalized_tire_load = x.m_normalized_tire_load; + m_torque = x.m_torque; + m_long_force = x.m_long_force; + m_lat_force = x.m_lat_force; + m_normalized_long_force = x.m_normalized_long_force; + m_normalized_lat_force = x.m_normalized_lat_force; +} + +carla_msgs::msg::CarlaVehicleTelemetryDataWheel& carla_msgs::msg::CarlaVehicleTelemetryDataWheel::operator =( + const CarlaVehicleTelemetryDataWheel& x) +{ + + m_tire_friction = x.m_tire_friction; + m_lat_slip = x.m_lat_slip; + m_long_slip = x.m_long_slip; + m_omega = x.m_omega; + m_tire_load = x.m_tire_load; + m_normalized_tire_load = x.m_normalized_tire_load; + m_torque = x.m_torque; + m_long_force = x.m_long_force; + m_lat_force = x.m_lat_force; + m_normalized_long_force = x.m_normalized_long_force; + m_normalized_lat_force = x.m_normalized_lat_force; + + return *this; +} + +carla_msgs::msg::CarlaVehicleTelemetryDataWheel& carla_msgs::msg::CarlaVehicleTelemetryDataWheel::operator =( + CarlaVehicleTelemetryDataWheel&& x) +{ + + m_tire_friction = x.m_tire_friction; + m_lat_slip = x.m_lat_slip; + m_long_slip = x.m_long_slip; + m_omega = x.m_omega; + m_tire_load = x.m_tire_load; + m_normalized_tire_load = x.m_normalized_tire_load; + m_torque = x.m_torque; + m_long_force = x.m_long_force; + m_lat_force = x.m_lat_force; + m_normalized_long_force = x.m_normalized_long_force; + m_normalized_lat_force = x.m_normalized_lat_force; + + return *this; +} + +bool carla_msgs::msg::CarlaVehicleTelemetryDataWheel::operator ==( + const CarlaVehicleTelemetryDataWheel& x) const +{ + + return (m_tire_friction == x.m_tire_friction && m_lat_slip == x.m_lat_slip && m_long_slip == x.m_long_slip && m_omega == x.m_omega && m_tire_load == x.m_tire_load && m_normalized_tire_load == x.m_normalized_tire_load && m_torque == x.m_torque && m_long_force == x.m_long_force && m_lat_force == x.m_lat_force && m_normalized_long_force == x.m_normalized_long_force && m_normalized_lat_force == x.m_normalized_lat_force); +} + +bool carla_msgs::msg::CarlaVehicleTelemetryDataWheel::operator !=( + const CarlaVehicleTelemetryDataWheel& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaVehicleTelemetryDataWheel::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaVehicleTelemetryDataWheel::getCdrSerializedSize( + const carla_msgs::msg::CarlaVehicleTelemetryDataWheel& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaVehicleTelemetryDataWheel::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_tire_friction; + scdr << m_lat_slip; + scdr << m_long_slip; + scdr << m_omega; + scdr << m_tire_load; + scdr << m_normalized_tire_load; + scdr << m_torque; + scdr << m_long_force; + scdr << m_lat_force; + scdr << m_normalized_long_force; + scdr << m_normalized_lat_force; + +} + +void carla_msgs::msg::CarlaVehicleTelemetryDataWheel::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_tire_friction; + dcdr >> m_lat_slip; + dcdr >> m_long_slip; + dcdr >> m_omega; + dcdr >> m_tire_load; + dcdr >> m_normalized_tire_load; + dcdr >> m_torque; + dcdr >> m_long_force; + dcdr >> m_lat_force; + dcdr >> m_normalized_long_force; + dcdr >> m_normalized_lat_force; +} + +/*! + * @brief This function sets a value in member tire_friction + * @param _tire_friction New value for member tire_friction + */ +void carla_msgs::msg::CarlaVehicleTelemetryDataWheel::tire_friction( + float _tire_friction) +{ + m_tire_friction = _tire_friction; +} + +/*! + * @brief This function returns the value of member tire_friction + * @return Value of member tire_friction + */ +float carla_msgs::msg::CarlaVehicleTelemetryDataWheel::tire_friction() const +{ + return m_tire_friction; +} + +/*! + * @brief This function returns a reference to member tire_friction + * @return Reference to member tire_friction + */ +float& carla_msgs::msg::CarlaVehicleTelemetryDataWheel::tire_friction() +{ + return m_tire_friction; +} + +/*! + * @brief This function sets a value in member lat_slip + * @param _lat_slip New value for member lat_slip + */ +void carla_msgs::msg::CarlaVehicleTelemetryDataWheel::lat_slip( + float _lat_slip) +{ + m_lat_slip = _lat_slip; +} + +/*! + * @brief This function returns the value of member lat_slip + * @return Value of member lat_slip + */ +float carla_msgs::msg::CarlaVehicleTelemetryDataWheel::lat_slip() const +{ + return m_lat_slip; +} + +/*! + * @brief This function returns a reference to member lat_slip + * @return Reference to member lat_slip + */ +float& carla_msgs::msg::CarlaVehicleTelemetryDataWheel::lat_slip() +{ + return m_lat_slip; +} + +/*! + * @brief This function sets a value in member long_slip + * @param _long_slip New value for member long_slip + */ +void carla_msgs::msg::CarlaVehicleTelemetryDataWheel::long_slip( + float _long_slip) +{ + m_long_slip = _long_slip; +} + +/*! + * @brief This function returns the value of member long_slip + * @return Value of member long_slip + */ +float carla_msgs::msg::CarlaVehicleTelemetryDataWheel::long_slip() const +{ + return m_long_slip; +} + +/*! + * @brief This function returns a reference to member long_slip + * @return Reference to member long_slip + */ +float& carla_msgs::msg::CarlaVehicleTelemetryDataWheel::long_slip() +{ + return m_long_slip; +} + +/*! + * @brief This function sets a value in member omega + * @param _omega New value for member omega + */ +void carla_msgs::msg::CarlaVehicleTelemetryDataWheel::omega( + float _omega) +{ + m_omega = _omega; +} + +/*! + * @brief This function returns the value of member omega + * @return Value of member omega + */ +float carla_msgs::msg::CarlaVehicleTelemetryDataWheel::omega() const +{ + return m_omega; +} + +/*! + * @brief This function returns a reference to member omega + * @return Reference to member omega + */ +float& carla_msgs::msg::CarlaVehicleTelemetryDataWheel::omega() +{ + return m_omega; +} + +/*! + * @brief This function sets a value in member tire_load + * @param _tire_load New value for member tire_load + */ +void carla_msgs::msg::CarlaVehicleTelemetryDataWheel::tire_load( + float _tire_load) +{ + m_tire_load = _tire_load; +} + +/*! + * @brief This function returns the value of member tire_load + * @return Value of member tire_load + */ +float carla_msgs::msg::CarlaVehicleTelemetryDataWheel::tire_load() const +{ + return m_tire_load; +} + +/*! + * @brief This function returns a reference to member tire_load + * @return Reference to member tire_load + */ +float& carla_msgs::msg::CarlaVehicleTelemetryDataWheel::tire_load() +{ + return m_tire_load; +} + +/*! + * @brief This function sets a value in member normalized_tire_load + * @param _normalized_tire_load New value for member normalized_tire_load + */ +void carla_msgs::msg::CarlaVehicleTelemetryDataWheel::normalized_tire_load( + float _normalized_tire_load) +{ + m_normalized_tire_load = _normalized_tire_load; +} + +/*! + * @brief This function returns the value of member normalized_tire_load + * @return Value of member normalized_tire_load + */ +float carla_msgs::msg::CarlaVehicleTelemetryDataWheel::normalized_tire_load() const +{ + return m_normalized_tire_load; +} + +/*! + * @brief This function returns a reference to member normalized_tire_load + * @return Reference to member normalized_tire_load + */ +float& carla_msgs::msg::CarlaVehicleTelemetryDataWheel::normalized_tire_load() +{ + return m_normalized_tire_load; +} + +/*! + * @brief This function sets a value in member torque + * @param _torque New value for member torque + */ +void carla_msgs::msg::CarlaVehicleTelemetryDataWheel::torque( + float _torque) +{ + m_torque = _torque; +} + +/*! + * @brief This function returns the value of member torque + * @return Value of member torque + */ +float carla_msgs::msg::CarlaVehicleTelemetryDataWheel::torque() const +{ + return m_torque; +} + +/*! + * @brief This function returns a reference to member torque + * @return Reference to member torque + */ +float& carla_msgs::msg::CarlaVehicleTelemetryDataWheel::torque() +{ + return m_torque; +} + +/*! + * @brief This function sets a value in member long_force + * @param _long_force New value for member long_force + */ +void carla_msgs::msg::CarlaVehicleTelemetryDataWheel::long_force( + float _long_force) +{ + m_long_force = _long_force; +} + +/*! + * @brief This function returns the value of member long_force + * @return Value of member long_force + */ +float carla_msgs::msg::CarlaVehicleTelemetryDataWheel::long_force() const +{ + return m_long_force; +} + +/*! + * @brief This function returns a reference to member long_force + * @return Reference to member long_force + */ +float& carla_msgs::msg::CarlaVehicleTelemetryDataWheel::long_force() +{ + return m_long_force; +} + +/*! + * @brief This function sets a value in member lat_force + * @param _lat_force New value for member lat_force + */ +void carla_msgs::msg::CarlaVehicleTelemetryDataWheel::lat_force( + float _lat_force) +{ + m_lat_force = _lat_force; +} + +/*! + * @brief This function returns the value of member lat_force + * @return Value of member lat_force + */ +float carla_msgs::msg::CarlaVehicleTelemetryDataWheel::lat_force() const +{ + return m_lat_force; +} + +/*! + * @brief This function returns a reference to member lat_force + * @return Reference to member lat_force + */ +float& carla_msgs::msg::CarlaVehicleTelemetryDataWheel::lat_force() +{ + return m_lat_force; +} + +/*! + * @brief This function sets a value in member normalized_long_force + * @param _normalized_long_force New value for member normalized_long_force + */ +void carla_msgs::msg::CarlaVehicleTelemetryDataWheel::normalized_long_force( + float _normalized_long_force) +{ + m_normalized_long_force = _normalized_long_force; +} + +/*! + * @brief This function returns the value of member normalized_long_force + * @return Value of member normalized_long_force + */ +float carla_msgs::msg::CarlaVehicleTelemetryDataWheel::normalized_long_force() const +{ + return m_normalized_long_force; +} + +/*! + * @brief This function returns a reference to member normalized_long_force + * @return Reference to member normalized_long_force + */ +float& carla_msgs::msg::CarlaVehicleTelemetryDataWheel::normalized_long_force() +{ + return m_normalized_long_force; +} + +/*! + * @brief This function sets a value in member normalized_lat_force + * @param _normalized_lat_force New value for member normalized_lat_force + */ +void carla_msgs::msg::CarlaVehicleTelemetryDataWheel::normalized_lat_force( + float _normalized_lat_force) +{ + m_normalized_lat_force = _normalized_lat_force; +} + +/*! + * @brief This function returns the value of member normalized_lat_force + * @return Value of member normalized_lat_force + */ +float carla_msgs::msg::CarlaVehicleTelemetryDataWheel::normalized_lat_force() const +{ + return m_normalized_lat_force; +} + +/*! + * @brief This function returns a reference to member normalized_lat_force + * @return Reference to member normalized_lat_force + */ +float& carla_msgs::msg::CarlaVehicleTelemetryDataWheel::normalized_lat_force() +{ + return m_normalized_lat_force; +} + + +size_t carla_msgs::msg::CarlaVehicleTelemetryDataWheel::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaVehicleTelemetryDataWheel::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaVehicleTelemetryDataWheel::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryDataWheel.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryDataWheel.h new file mode 100644 index 00000000000..ecab69d1332 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryDataWheel.h @@ -0,0 +1,410 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleTelemetryDataWheel.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLETELEMETRYDATAWHEEL_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLETELEMETRYDATAWHEEL_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CarlaVehicleTelemetryDataWheel_SOURCE) +#define CarlaVehicleTelemetryDataWheel_DllAPI __declspec( dllexport ) +#else +#define CarlaVehicleTelemetryDataWheel_DllAPI __declspec( dllimport ) +#endif // CarlaVehicleTelemetryDataWheel_SOURCE +#else +#define CarlaVehicleTelemetryDataWheel_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CarlaVehicleTelemetryDataWheel_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace msg { + /*! + * @brief This class represents the structure CarlaVehicleTelemetryDataWheel defined by the user in the IDL file. + * @ingroup CARLAVEHICLETELEMETRYDATAWHEEL + */ + class CarlaVehicleTelemetryDataWheel + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaVehicleTelemetryDataWheel(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaVehicleTelemetryDataWheel(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleTelemetryDataWheel that will be copied. + */ + eProsima_user_DllExport CarlaVehicleTelemetryDataWheel( + const CarlaVehicleTelemetryDataWheel& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleTelemetryDataWheel that will be copied. + */ + eProsima_user_DllExport CarlaVehicleTelemetryDataWheel( + CarlaVehicleTelemetryDataWheel&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleTelemetryDataWheel that will be copied. + */ + eProsima_user_DllExport CarlaVehicleTelemetryDataWheel& operator =( + const CarlaVehicleTelemetryDataWheel& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaVehicleTelemetryDataWheel that will be copied. + */ + eProsima_user_DllExport CarlaVehicleTelemetryDataWheel& operator =( + CarlaVehicleTelemetryDataWheel&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaVehicleTelemetryDataWheel object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaVehicleTelemetryDataWheel& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaVehicleTelemetryDataWheel object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaVehicleTelemetryDataWheel& x) const; + + /*! + * @brief This function sets a value in member tire_friction + * @param _tire_friction New value for member tire_friction + */ + eProsima_user_DllExport void tire_friction( + float _tire_friction); + + /*! + * @brief This function returns the value of member tire_friction + * @return Value of member tire_friction + */ + eProsima_user_DllExport float tire_friction() const; + + /*! + * @brief This function returns a reference to member tire_friction + * @return Reference to member tire_friction + */ + eProsima_user_DllExport float& tire_friction(); + + /*! + * @brief This function sets a value in member lat_slip + * @param _lat_slip New value for member lat_slip + */ + eProsima_user_DllExport void lat_slip( + float _lat_slip); + + /*! + * @brief This function returns the value of member lat_slip + * @return Value of member lat_slip + */ + eProsima_user_DllExport float lat_slip() const; + + /*! + * @brief This function returns a reference to member lat_slip + * @return Reference to member lat_slip + */ + eProsima_user_DllExport float& lat_slip(); + + /*! + * @brief This function sets a value in member long_slip + * @param _long_slip New value for member long_slip + */ + eProsima_user_DllExport void long_slip( + float _long_slip); + + /*! + * @brief This function returns the value of member long_slip + * @return Value of member long_slip + */ + eProsima_user_DllExport float long_slip() const; + + /*! + * @brief This function returns a reference to member long_slip + * @return Reference to member long_slip + */ + eProsima_user_DllExport float& long_slip(); + + /*! + * @brief This function sets a value in member omega + * @param _omega New value for member omega + */ + eProsima_user_DllExport void omega( + float _omega); + + /*! + * @brief This function returns the value of member omega + * @return Value of member omega + */ + eProsima_user_DllExport float omega() const; + + /*! + * @brief This function returns a reference to member omega + * @return Reference to member omega + */ + eProsima_user_DllExport float& omega(); + + /*! + * @brief This function sets a value in member tire_load + * @param _tire_load New value for member tire_load + */ + eProsima_user_DllExport void tire_load( + float _tire_load); + + /*! + * @brief This function returns the value of member tire_load + * @return Value of member tire_load + */ + eProsima_user_DllExport float tire_load() const; + + /*! + * @brief This function returns a reference to member tire_load + * @return Reference to member tire_load + */ + eProsima_user_DllExport float& tire_load(); + + /*! + * @brief This function sets a value in member normalized_tire_load + * @param _normalized_tire_load New value for member normalized_tire_load + */ + eProsima_user_DllExport void normalized_tire_load( + float _normalized_tire_load); + + /*! + * @brief This function returns the value of member normalized_tire_load + * @return Value of member normalized_tire_load + */ + eProsima_user_DllExport float normalized_tire_load() const; + + /*! + * @brief This function returns a reference to member normalized_tire_load + * @return Reference to member normalized_tire_load + */ + eProsima_user_DllExport float& normalized_tire_load(); + + /*! + * @brief This function sets a value in member torque + * @param _torque New value for member torque + */ + eProsima_user_DllExport void torque( + float _torque); + + /*! + * @brief This function returns the value of member torque + * @return Value of member torque + */ + eProsima_user_DllExport float torque() const; + + /*! + * @brief This function returns a reference to member torque + * @return Reference to member torque + */ + eProsima_user_DllExport float& torque(); + + /*! + * @brief This function sets a value in member long_force + * @param _long_force New value for member long_force + */ + eProsima_user_DllExport void long_force( + float _long_force); + + /*! + * @brief This function returns the value of member long_force + * @return Value of member long_force + */ + eProsima_user_DllExport float long_force() const; + + /*! + * @brief This function returns a reference to member long_force + * @return Reference to member long_force + */ + eProsima_user_DllExport float& long_force(); + + /*! + * @brief This function sets a value in member lat_force + * @param _lat_force New value for member lat_force + */ + eProsima_user_DllExport void lat_force( + float _lat_force); + + /*! + * @brief This function returns the value of member lat_force + * @return Value of member lat_force + */ + eProsima_user_DllExport float lat_force() const; + + /*! + * @brief This function returns a reference to member lat_force + * @return Reference to member lat_force + */ + eProsima_user_DllExport float& lat_force(); + + /*! + * @brief This function sets a value in member normalized_long_force + * @param _normalized_long_force New value for member normalized_long_force + */ + eProsima_user_DllExport void normalized_long_force( + float _normalized_long_force); + + /*! + * @brief This function returns the value of member normalized_long_force + * @return Value of member normalized_long_force + */ + eProsima_user_DllExport float normalized_long_force() const; + + /*! + * @brief This function returns a reference to member normalized_long_force + * @return Reference to member normalized_long_force + */ + eProsima_user_DllExport float& normalized_long_force(); + + /*! + * @brief This function sets a value in member normalized_lat_force + * @param _normalized_lat_force New value for member normalized_lat_force + */ + eProsima_user_DllExport void normalized_lat_force( + float _normalized_lat_force); + + /*! + * @brief This function returns the value of member normalized_lat_force + * @return Value of member normalized_lat_force + */ + eProsima_user_DllExport float normalized_lat_force() const; + + /*! + * @brief This function returns a reference to member normalized_lat_force + * @return Reference to member normalized_lat_force + */ + eProsima_user_DllExport float& normalized_lat_force(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::msg::CarlaVehicleTelemetryDataWheel& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + float m_tire_friction; + float m_lat_slip; + float m_long_slip; + float m_omega; + float m_tire_load; + float m_normalized_tire_load; + float m_torque; + float m_long_force; + float m_lat_force; + float m_normalized_long_force; + float m_normalized_lat_force; + }; + } // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLETELEMETRYDATAWHEEL_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryDataWheelPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryDataWheelPubSubTypes.cxx new file mode 100644 index 00000000000..02b26bb2b08 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryDataWheelPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleTelemetryDataWheelPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaVehicleTelemetryDataWheelPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaVehicleTelemetryDataWheelPubSubType::CarlaVehicleTelemetryDataWheelPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaVehicleTelemetryDataWheel_"); + auto type_size = CarlaVehicleTelemetryDataWheel::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaVehicleTelemetryDataWheel::isKeyDefined(); + size_t keyLength = CarlaVehicleTelemetryDataWheel::getKeyMaxCdrSerializedSize() > 16 ? + CarlaVehicleTelemetryDataWheel::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaVehicleTelemetryDataWheelPubSubType::~CarlaVehicleTelemetryDataWheelPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaVehicleTelemetryDataWheelPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaVehicleTelemetryDataWheel* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaVehicleTelemetryDataWheelPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaVehicleTelemetryDataWheel* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaVehicleTelemetryDataWheelPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaVehicleTelemetryDataWheelPubSubType::createData() + { + return reinterpret_cast(new CarlaVehicleTelemetryDataWheel()); + } + + void CarlaVehicleTelemetryDataWheelPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaVehicleTelemetryDataWheelPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaVehicleTelemetryDataWheel* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaVehicleTelemetryDataWheel::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaVehicleTelemetryDataWheel::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryDataWheelPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryDataWheelPubSubTypes.h new file mode 100644 index 00000000000..379110f0268 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaVehicleTelemetryDataWheelPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaVehicleTelemetryDataWheelPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLETELEMETRYDATAWHEEL_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLETELEMETRYDATAWHEEL_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaVehicleTelemetryDataWheel.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaVehicleTelemetryDataWheel is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CarlaVehicleTelemetryDataWheel defined by the user in the IDL file. + * @ingroup CARLAVEHICLETELEMETRYDATAWHEEL + */ + class CarlaVehicleTelemetryDataWheelPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaVehicleTelemetryDataWheel type; + + eProsima_user_DllExport CarlaVehicleTelemetryDataWheelPubSubType(); + + eProsima_user_DllExport virtual ~CarlaVehicleTelemetryDataWheelPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) CarlaVehicleTelemetryDataWheel(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAVEHICLETELEMETRYDATAWHEEL_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControl.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControl.cxx new file mode 100644 index 00000000000..5030a1713a3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControl.cxx @@ -0,0 +1,324 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaWalkerControl.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaWalkerControl.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaWalkerControl::CarlaWalkerControl() +{ + // m_header com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@563e4951 + + // m_direction com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@4066c471 + + // m_speed com.eprosima.idl.parser.typecode.PrimitiveTypeCode@2b175c00 + m_speed = 0.0; + // m_jump com.eprosima.idl.parser.typecode.PrimitiveTypeCode@3eb81efb + m_jump = false; + +} + +carla_msgs::msg::CarlaWalkerControl::~CarlaWalkerControl() +{ + + + +} + +carla_msgs::msg::CarlaWalkerControl::CarlaWalkerControl( + const CarlaWalkerControl& x) +{ + m_header = x.m_header; + m_direction = x.m_direction; + m_speed = x.m_speed; + m_jump = x.m_jump; +} + +carla_msgs::msg::CarlaWalkerControl::CarlaWalkerControl( + CarlaWalkerControl&& x) +{ + m_header = std::move(x.m_header); + m_direction = std::move(x.m_direction); + m_speed = x.m_speed; + m_jump = x.m_jump; +} + +carla_msgs::msg::CarlaWalkerControl& carla_msgs::msg::CarlaWalkerControl::operator =( + const CarlaWalkerControl& x) +{ + + m_header = x.m_header; + m_direction = x.m_direction; + m_speed = x.m_speed; + m_jump = x.m_jump; + + return *this; +} + +carla_msgs::msg::CarlaWalkerControl& carla_msgs::msg::CarlaWalkerControl::operator =( + CarlaWalkerControl&& x) +{ + + m_header = std::move(x.m_header); + m_direction = std::move(x.m_direction); + m_speed = x.m_speed; + m_jump = x.m_jump; + + return *this; +} + +bool carla_msgs::msg::CarlaWalkerControl::operator ==( + const CarlaWalkerControl& x) const +{ + + return (m_header == x.m_header && m_direction == x.m_direction && m_speed == x.m_speed && m_jump == x.m_jump); +} + +bool carla_msgs::msg::CarlaWalkerControl::operator !=( + const CarlaWalkerControl& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaWalkerControl::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getMaxCdrSerializedSize(current_alignment); + current_alignment += geometry_msgs::msg::Vector3::getMaxCdrSerializedSize(current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaWalkerControl::getCdrSerializedSize( + const carla_msgs::msg::CarlaWalkerControl& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getCdrSerializedSize(data.header(), current_alignment); + current_alignment += geometry_msgs::msg::Vector3::getCdrSerializedSize(data.direction(), current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaWalkerControl::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_header; + scdr << m_direction; + scdr << m_speed; + scdr << m_jump; + +} + +void carla_msgs::msg::CarlaWalkerControl::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_header; + dcdr >> m_direction; + dcdr >> m_speed; + dcdr >> m_jump; +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void carla_msgs::msg::CarlaWalkerControl::header( + const std_msgs::msg::Header& _header) +{ + m_header = _header; +} + +/*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ +void carla_msgs::msg::CarlaWalkerControl::header( + std_msgs::msg::Header&& _header) +{ + m_header = std::move(_header); +} + +/*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ +const std_msgs::msg::Header& carla_msgs::msg::CarlaWalkerControl::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& carla_msgs::msg::CarlaWalkerControl::header() +{ + return m_header; +} +/*! + * @brief This function copies the value in member direction + * @param _direction New value to be copied in member direction + */ +void carla_msgs::msg::CarlaWalkerControl::direction( + const geometry_msgs::msg::Vector3& _direction) +{ + m_direction = _direction; +} + +/*! + * @brief This function moves the value in member direction + * @param _direction New value to be moved in member direction + */ +void carla_msgs::msg::CarlaWalkerControl::direction( + geometry_msgs::msg::Vector3&& _direction) +{ + m_direction = std::move(_direction); +} + +/*! + * @brief This function returns a constant reference to member direction + * @return Constant reference to member direction + */ +const geometry_msgs::msg::Vector3& carla_msgs::msg::CarlaWalkerControl::direction() const +{ + return m_direction; +} + +/*! + * @brief This function returns a reference to member direction + * @return Reference to member direction + */ +geometry_msgs::msg::Vector3& carla_msgs::msg::CarlaWalkerControl::direction() +{ + return m_direction; +} +/*! + * @brief This function sets a value in member speed + * @param _speed New value for member speed + */ +void carla_msgs::msg::CarlaWalkerControl::speed( + float _speed) +{ + m_speed = _speed; +} + +/*! + * @brief This function returns the value of member speed + * @return Value of member speed + */ +float carla_msgs::msg::CarlaWalkerControl::speed() const +{ + return m_speed; +} + +/*! + * @brief This function returns a reference to member speed + * @return Reference to member speed + */ +float& carla_msgs::msg::CarlaWalkerControl::speed() +{ + return m_speed; +} + +/*! + * @brief This function sets a value in member jump + * @param _jump New value for member jump + */ +void carla_msgs::msg::CarlaWalkerControl::jump( + bool _jump) +{ + m_jump = _jump; +} + +/*! + * @brief This function returns the value of member jump + * @return Value of member jump + */ +bool carla_msgs::msg::CarlaWalkerControl::jump() const +{ + return m_jump; +} + +/*! + * @brief This function returns a reference to member jump + * @return Reference to member jump + */ +bool& carla_msgs::msg::CarlaWalkerControl::jump() +{ + return m_jump; +} + + +size_t carla_msgs::msg::CarlaWalkerControl::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaWalkerControl::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaWalkerControl::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/types/TransformStamped.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControl.h similarity index 56% rename from LibCarla/source/carla/ros2/types/TransformStamped.h rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControl.h index a5f1fd27e6f..262e21061da 100644 --- a/LibCarla/source/carla/ros2/types/TransformStamped.h +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControl.h @@ -13,19 +13,17 @@ // limitations under the License. /*! - * @file TransformStamped.h + * @file CarlaWalkerControl.h * This header file contains the declaration of the described types in the IDL file. * * This file was generated by the tool gen. */ -#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPED_H_ -#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPED_H_ +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWALKERCONTROL_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWALKERCONTROL_H_ -#include "Header.h" -#include "Transform.h" - -#include +#include "geometry_msgs/msg/Vector3.h" +#include "std_msgs/msg/Header.h" #include #include @@ -46,16 +44,16 @@ #if defined(_WIN32) #if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(TransformStamped_SOURCE) -#define TransformStamped_DllAPI __declspec( dllexport ) +#if defined(CarlaWalkerControl_SOURCE) +#define CarlaWalkerControl_DllAPI __declspec( dllexport ) #else -#define TransformStamped_DllAPI __declspec( dllimport ) -#endif // TransformStamped_SOURCE +#define CarlaWalkerControl_DllAPI __declspec( dllimport ) +#endif // CarlaWalkerControl_SOURCE #else -#define TransformStamped_DllAPI +#define CarlaWalkerControl_DllAPI #endif // EPROSIMA_USER_DLL_EXPORT #else -#define TransformStamped_DllAPI +#define CarlaWalkerControl_DllAPI #endif // _WIN32 namespace eprosima { @@ -64,67 +62,68 @@ class Cdr; } // namespace fastcdr } // namespace eprosima -namespace geometry_msgs { + +namespace carla_msgs { namespace msg { /*! - * @brief This class represents the structure TransformStamped defined by the user in the IDL file. - * @ingroup TRANSFORMSTAMPED + * @brief This class represents the structure CarlaWalkerControl defined by the user in the IDL file. + * @ingroup CARLAWALKERCONTROL */ - class TransformStamped + class CarlaWalkerControl { public: /*! * @brief Default constructor. */ - eProsima_user_DllExport TransformStamped(); + eProsima_user_DllExport CarlaWalkerControl(); /*! * @brief Default destructor. */ - eProsima_user_DllExport ~TransformStamped(); + eProsima_user_DllExport ~CarlaWalkerControl(); /*! * @brief Copy constructor. - * @param x Reference to the object geometry_msgs::msg::TransformStamped that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaWalkerControl that will be copied. */ - eProsima_user_DllExport TransformStamped( - const TransformStamped& x); + eProsima_user_DllExport CarlaWalkerControl( + const CarlaWalkerControl& x); /*! * @brief Move constructor. - * @param x Reference to the object geometry_msgs::msg::TransformStamped that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaWalkerControl that will be copied. */ - eProsima_user_DllExport TransformStamped( - TransformStamped&& x) noexcept; + eProsima_user_DllExport CarlaWalkerControl( + CarlaWalkerControl&& x); /*! * @brief Copy assignment. - * @param x Reference to the object geometry_msgs::msg::TransformStamped that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaWalkerControl that will be copied. */ - eProsima_user_DllExport TransformStamped& operator =( - const TransformStamped& x); + eProsima_user_DllExport CarlaWalkerControl& operator =( + const CarlaWalkerControl& x); /*! * @brief Move assignment. - * @param x Reference to the object geometry_msgs::msg::TransformStamped that will be copied. + * @param x Reference to the object carla_msgs::msg::CarlaWalkerControl that will be copied. */ - eProsima_user_DllExport TransformStamped& operator =( - TransformStamped&& x) noexcept; + eProsima_user_DllExport CarlaWalkerControl& operator =( + CarlaWalkerControl&& x); /*! * @brief Comparison operator. - * @param x geometry_msgs::msg::TransformStamped object to compare. + * @param x carla_msgs::msg::CarlaWalkerControl object to compare. */ eProsima_user_DllExport bool operator ==( - const TransformStamped& x) const; + const CarlaWalkerControl& x) const; /*! * @brief Comparison operator. - * @param x geometry_msgs::msg::TransformStamped object to compare. + * @param x carla_msgs::msg::CarlaWalkerControl object to compare. */ eProsima_user_DllExport bool operator !=( - const TransformStamped& x) const; + const CarlaWalkerControl& x) const; /*! * @brief This function copies the value in member header @@ -152,62 +151,75 @@ namespace geometry_msgs { */ eProsima_user_DllExport std_msgs::msg::Header& header(); /*! - * @brief This function copies the value in member child_frame_id - * @param _child_frame_id New value to be copied in member child_frame_id + * @brief This function copies the value in member direction + * @param _direction New value to be copied in member direction */ - eProsima_user_DllExport void child_frame_id( - const std::string& _child_frame_id); + eProsima_user_DllExport void direction( + const geometry_msgs::msg::Vector3& _direction); /*! - * @brief This function moves the value in member child_frame_id - * @param _child_frame_id New value to be moved in member child_frame_id + * @brief This function moves the value in member direction + * @param _direction New value to be moved in member direction */ - eProsima_user_DllExport void child_frame_id( - std::string&& _child_frame_id); + eProsima_user_DllExport void direction( + geometry_msgs::msg::Vector3&& _direction); /*! - * @brief This function returns a constant reference to member child_frame_id - * @return Constant reference to member child_frame_id + * @brief This function returns a constant reference to member direction + * @return Constant reference to member direction */ - eProsima_user_DllExport const std::string& child_frame_id() const; + eProsima_user_DllExport const geometry_msgs::msg::Vector3& direction() const; /*! - * @brief This function returns a reference to member child_frame_id - * @return Reference to member child_frame_id + * @brief This function returns a reference to member direction + * @return Reference to member direction */ - eProsima_user_DllExport std::string& child_frame_id(); + eProsima_user_DllExport geometry_msgs::msg::Vector3& direction(); + /*! + * @brief This function sets a value in member speed + * @param _speed New value for member speed + */ + eProsima_user_DllExport void speed( + float _speed); + /*! - * @brief This function copies the value in member transform - * @param _transform New value to be copied in member transform + * @brief This function returns the value of member speed + * @return Value of member speed */ - eProsima_user_DllExport void transform( - const geometry_msgs::msg::Transform& _transform); + eProsima_user_DllExport float speed() const; /*! - * @brief This function moves the value in member transform - * @param _transform New value to be moved in member transform + * @brief This function returns a reference to member speed + * @return Reference to member speed */ - eProsima_user_DllExport void transform( - geometry_msgs::msg::Transform&& _transform); + eProsima_user_DllExport float& speed(); /*! - * @brief This function returns a constant reference to member transform - * @return Constant reference to member transform + * @brief This function sets a value in member jump + * @param _jump New value for member jump */ - eProsima_user_DllExport const geometry_msgs::msg::Transform& transform() const; + eProsima_user_DllExport void jump( + bool _jump); /*! - * @brief This function returns a reference to member transform - * @return Reference to member transform + * @brief This function returns the value of member jump + * @return Value of member jump */ - eProsima_user_DllExport geometry_msgs::msg::Transform& transform(); + eProsima_user_DllExport bool jump() const; + + /*! + * @brief This function returns a reference to member jump + * @return Reference to member jump + */ + eProsima_user_DllExport bool& jump(); + /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -218,9 +230,10 @@ namespace geometry_msgs { * @return Serialized size. */ eProsima_user_DllExport static size_t getCdrSerializedSize( - const geometry_msgs::msg::TransformStamped& data, + const carla_msgs::msg::CarlaWalkerControl& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -235,6 +248,8 @@ namespace geometry_msgs { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -257,12 +272,13 @@ namespace geometry_msgs { eprosima::fastcdr::Cdr& cdr) const; private: - std_msgs::msg::Header m_header; - std::string m_child_frame_id; - geometry_msgs::msg::Transform m_transform; + std_msgs::msg::Header m_header; + geometry_msgs::msg::Vector3 m_direction; + float m_speed; + bool m_jump; }; } // namespace msg -} // namespace geometry_msgs +} // namespace carla_msgs -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPED_H_ +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWALKERCONTROL_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControlPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControlPubSubTypes.cxx new file mode 100644 index 00000000000..20477573866 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControlPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaWalkerControlPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaWalkerControlPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaWalkerControlPubSubType::CarlaWalkerControlPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaWalkerControl_"); + auto type_size = CarlaWalkerControl::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaWalkerControl::isKeyDefined(); + size_t keyLength = CarlaWalkerControl::getKeyMaxCdrSerializedSize() > 16 ? + CarlaWalkerControl::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaWalkerControlPubSubType::~CarlaWalkerControlPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaWalkerControlPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaWalkerControl* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaWalkerControlPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaWalkerControl* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaWalkerControlPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaWalkerControlPubSubType::createData() + { + return reinterpret_cast(new CarlaWalkerControl()); + } + + void CarlaWalkerControlPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaWalkerControlPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaWalkerControl* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaWalkerControl::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaWalkerControl::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/types/OdometryPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControlPubSubTypes.h similarity index 77% rename from LibCarla/source/carla/ros2/types/OdometryPubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControlPubSubTypes.h index 2c333fe0cf1..e9aff523706 100644 --- a/LibCarla/source/carla/ros2/types/OdometryPubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControlPubSubTypes.h @@ -13,46 +13,43 @@ // limitations under the License. /*! - * @file OdometryPubSubTypes.h + * @file CarlaWalkerControlPubSubTypes.h * This header file contains the declaration of the serialization functions. * * This file was generated by the tool fastcdrgen. */ -#ifndef _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRY_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRY_PUBSUBTYPES_H_ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWALKERCONTROL_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWALKERCONTROL_PUBSUBTYPES_H_ #include #include -#include "Odometry.h" -#include "PoseWithCovariancePubSubTypes.h" -#include "TwistWithCovariancePubSubTypes.h" -#include "HeaderPubSubTypes.h" +#include "CarlaWalkerControl.h" #if !defined(GEN_API_VER) || (GEN_API_VER != 1) #error \ - Generated Odometry is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. + Generated CarlaWalkerControl is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. #endif // GEN_API_VER -namespace nav_msgs +namespace carla_msgs { namespace msg { - /*! - * @brief This class represents the TopicDataType of the type Odometry defined by the user in the IDL file. - * @ingroup ODOMETRY + * @brief This class represents the TopicDataType of the type CarlaWalkerControl defined by the user in the IDL file. + * @ingroup CARLAWALKERCONTROL */ - class OdometryPubSubType : public eprosima::fastdds::dds::TopicDataType + class CarlaWalkerControlPubSubType : public eprosima::fastdds::dds::TopicDataType { public: - typedef Odometry type; + typedef CarlaWalkerControl type; - eProsima_user_DllExport OdometryPubSubType(); + eProsima_user_DllExport CarlaWalkerControlPubSubType(); - eProsima_user_DllExport virtual ~OdometryPubSubType() override; + eProsima_user_DllExport virtual ~CarlaWalkerControlPubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -100,10 +97,11 @@ namespace nav_msgs } #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; unsigned char* m_keyBuffer; }; } } -#endif // _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRY_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWALKERCONTROL_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParameters.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParameters.cxx new file mode 100644 index 00000000000..7b7f005acb6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParameters.cxx @@ -0,0 +1,529 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaWeatherParameters.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaWeatherParameters.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaWeatherParameters::CarlaWeatherParameters() +{ + // m_cloudiness com.eprosima.idl.parser.typecode.PrimitiveTypeCode@30bce90b + m_cloudiness = 0.0; + // m_precipitation com.eprosima.idl.parser.typecode.PrimitiveTypeCode@3e6f3f28 + m_precipitation = 0.0; + // m_precipitation_deposits com.eprosima.idl.parser.typecode.PrimitiveTypeCode@7e19ebf0 + m_precipitation_deposits = 0.0; + // m_wind_intensity com.eprosima.idl.parser.typecode.PrimitiveTypeCode@2474f125 + m_wind_intensity = 0.0; + // m_fog_density com.eprosima.idl.parser.typecode.PrimitiveTypeCode@7357a011 + m_fog_density = 0.0; + // m_fog_distance com.eprosima.idl.parser.typecode.PrimitiveTypeCode@3406472c + m_fog_distance = 0.0; + // m_wetness com.eprosima.idl.parser.typecode.PrimitiveTypeCode@5717c37 + m_wetness = 0.0; + // m_sun_azimuth_angle com.eprosima.idl.parser.typecode.PrimitiveTypeCode@68f4865 + m_sun_azimuth_angle = 0.0; + // m_sun_altitude_angle com.eprosima.idl.parser.typecode.PrimitiveTypeCode@4816278d + m_sun_altitude_angle = 0.0; + +} + +carla_msgs::msg::CarlaWeatherParameters::~CarlaWeatherParameters() +{ + + + + + + + + +} + +carla_msgs::msg::CarlaWeatherParameters::CarlaWeatherParameters( + const CarlaWeatherParameters& x) +{ + m_cloudiness = x.m_cloudiness; + m_precipitation = x.m_precipitation; + m_precipitation_deposits = x.m_precipitation_deposits; + m_wind_intensity = x.m_wind_intensity; + m_fog_density = x.m_fog_density; + m_fog_distance = x.m_fog_distance; + m_wetness = x.m_wetness; + m_sun_azimuth_angle = x.m_sun_azimuth_angle; + m_sun_altitude_angle = x.m_sun_altitude_angle; +} + +carla_msgs::msg::CarlaWeatherParameters::CarlaWeatherParameters( + CarlaWeatherParameters&& x) +{ + m_cloudiness = x.m_cloudiness; + m_precipitation = x.m_precipitation; + m_precipitation_deposits = x.m_precipitation_deposits; + m_wind_intensity = x.m_wind_intensity; + m_fog_density = x.m_fog_density; + m_fog_distance = x.m_fog_distance; + m_wetness = x.m_wetness; + m_sun_azimuth_angle = x.m_sun_azimuth_angle; + m_sun_altitude_angle = x.m_sun_altitude_angle; +} + +carla_msgs::msg::CarlaWeatherParameters& carla_msgs::msg::CarlaWeatherParameters::operator =( + const CarlaWeatherParameters& x) +{ + + m_cloudiness = x.m_cloudiness; + m_precipitation = x.m_precipitation; + m_precipitation_deposits = x.m_precipitation_deposits; + m_wind_intensity = x.m_wind_intensity; + m_fog_density = x.m_fog_density; + m_fog_distance = x.m_fog_distance; + m_wetness = x.m_wetness; + m_sun_azimuth_angle = x.m_sun_azimuth_angle; + m_sun_altitude_angle = x.m_sun_altitude_angle; + + return *this; +} + +carla_msgs::msg::CarlaWeatherParameters& carla_msgs::msg::CarlaWeatherParameters::operator =( + CarlaWeatherParameters&& x) +{ + + m_cloudiness = x.m_cloudiness; + m_precipitation = x.m_precipitation; + m_precipitation_deposits = x.m_precipitation_deposits; + m_wind_intensity = x.m_wind_intensity; + m_fog_density = x.m_fog_density; + m_fog_distance = x.m_fog_distance; + m_wetness = x.m_wetness; + m_sun_azimuth_angle = x.m_sun_azimuth_angle; + m_sun_altitude_angle = x.m_sun_altitude_angle; + + return *this; +} + +bool carla_msgs::msg::CarlaWeatherParameters::operator ==( + const CarlaWeatherParameters& x) const +{ + + return (m_cloudiness == x.m_cloudiness && m_precipitation == x.m_precipitation && m_precipitation_deposits == x.m_precipitation_deposits && m_wind_intensity == x.m_wind_intensity && m_fog_density == x.m_fog_density && m_fog_distance == x.m_fog_distance && m_wetness == x.m_wetness && m_sun_azimuth_angle == x.m_sun_azimuth_angle && m_sun_altitude_angle == x.m_sun_altitude_angle); +} + +bool carla_msgs::msg::CarlaWeatherParameters::operator !=( + const CarlaWeatherParameters& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaWeatherParameters::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaWeatherParameters::getCdrSerializedSize( + const carla_msgs::msg::CarlaWeatherParameters& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaWeatherParameters::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_cloudiness; + scdr << m_precipitation; + scdr << m_precipitation_deposits; + scdr << m_wind_intensity; + scdr << m_fog_density; + scdr << m_fog_distance; + scdr << m_wetness; + scdr << m_sun_azimuth_angle; + scdr << m_sun_altitude_angle; + +} + +void carla_msgs::msg::CarlaWeatherParameters::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_cloudiness; + dcdr >> m_precipitation; + dcdr >> m_precipitation_deposits; + dcdr >> m_wind_intensity; + dcdr >> m_fog_density; + dcdr >> m_fog_distance; + dcdr >> m_wetness; + dcdr >> m_sun_azimuth_angle; + dcdr >> m_sun_altitude_angle; +} + +/*! + * @brief This function sets a value in member cloudiness + * @param _cloudiness New value for member cloudiness + */ +void carla_msgs::msg::CarlaWeatherParameters::cloudiness( + float _cloudiness) +{ + m_cloudiness = _cloudiness; +} + +/*! + * @brief This function returns the value of member cloudiness + * @return Value of member cloudiness + */ +float carla_msgs::msg::CarlaWeatherParameters::cloudiness() const +{ + return m_cloudiness; +} + +/*! + * @brief This function returns a reference to member cloudiness + * @return Reference to member cloudiness + */ +float& carla_msgs::msg::CarlaWeatherParameters::cloudiness() +{ + return m_cloudiness; +} + +/*! + * @brief This function sets a value in member precipitation + * @param _precipitation New value for member precipitation + */ +void carla_msgs::msg::CarlaWeatherParameters::precipitation( + float _precipitation) +{ + m_precipitation = _precipitation; +} + +/*! + * @brief This function returns the value of member precipitation + * @return Value of member precipitation + */ +float carla_msgs::msg::CarlaWeatherParameters::precipitation() const +{ + return m_precipitation; +} + +/*! + * @brief This function returns a reference to member precipitation + * @return Reference to member precipitation + */ +float& carla_msgs::msg::CarlaWeatherParameters::precipitation() +{ + return m_precipitation; +} + +/*! + * @brief This function sets a value in member precipitation_deposits + * @param _precipitation_deposits New value for member precipitation_deposits + */ +void carla_msgs::msg::CarlaWeatherParameters::precipitation_deposits( + float _precipitation_deposits) +{ + m_precipitation_deposits = _precipitation_deposits; +} + +/*! + * @brief This function returns the value of member precipitation_deposits + * @return Value of member precipitation_deposits + */ +float carla_msgs::msg::CarlaWeatherParameters::precipitation_deposits() const +{ + return m_precipitation_deposits; +} + +/*! + * @brief This function returns a reference to member precipitation_deposits + * @return Reference to member precipitation_deposits + */ +float& carla_msgs::msg::CarlaWeatherParameters::precipitation_deposits() +{ + return m_precipitation_deposits; +} + +/*! + * @brief This function sets a value in member wind_intensity + * @param _wind_intensity New value for member wind_intensity + */ +void carla_msgs::msg::CarlaWeatherParameters::wind_intensity( + float _wind_intensity) +{ + m_wind_intensity = _wind_intensity; +} + +/*! + * @brief This function returns the value of member wind_intensity + * @return Value of member wind_intensity + */ +float carla_msgs::msg::CarlaWeatherParameters::wind_intensity() const +{ + return m_wind_intensity; +} + +/*! + * @brief This function returns a reference to member wind_intensity + * @return Reference to member wind_intensity + */ +float& carla_msgs::msg::CarlaWeatherParameters::wind_intensity() +{ + return m_wind_intensity; +} + +/*! + * @brief This function sets a value in member fog_density + * @param _fog_density New value for member fog_density + */ +void carla_msgs::msg::CarlaWeatherParameters::fog_density( + float _fog_density) +{ + m_fog_density = _fog_density; +} + +/*! + * @brief This function returns the value of member fog_density + * @return Value of member fog_density + */ +float carla_msgs::msg::CarlaWeatherParameters::fog_density() const +{ + return m_fog_density; +} + +/*! + * @brief This function returns a reference to member fog_density + * @return Reference to member fog_density + */ +float& carla_msgs::msg::CarlaWeatherParameters::fog_density() +{ + return m_fog_density; +} + +/*! + * @brief This function sets a value in member fog_distance + * @param _fog_distance New value for member fog_distance + */ +void carla_msgs::msg::CarlaWeatherParameters::fog_distance( + float _fog_distance) +{ + m_fog_distance = _fog_distance; +} + +/*! + * @brief This function returns the value of member fog_distance + * @return Value of member fog_distance + */ +float carla_msgs::msg::CarlaWeatherParameters::fog_distance() const +{ + return m_fog_distance; +} + +/*! + * @brief This function returns a reference to member fog_distance + * @return Reference to member fog_distance + */ +float& carla_msgs::msg::CarlaWeatherParameters::fog_distance() +{ + return m_fog_distance; +} + +/*! + * @brief This function sets a value in member wetness + * @param _wetness New value for member wetness + */ +void carla_msgs::msg::CarlaWeatherParameters::wetness( + float _wetness) +{ + m_wetness = _wetness; +} + +/*! + * @brief This function returns the value of member wetness + * @return Value of member wetness + */ +float carla_msgs::msg::CarlaWeatherParameters::wetness() const +{ + return m_wetness; +} + +/*! + * @brief This function returns a reference to member wetness + * @return Reference to member wetness + */ +float& carla_msgs::msg::CarlaWeatherParameters::wetness() +{ + return m_wetness; +} + +/*! + * @brief This function sets a value in member sun_azimuth_angle + * @param _sun_azimuth_angle New value for member sun_azimuth_angle + */ +void carla_msgs::msg::CarlaWeatherParameters::sun_azimuth_angle( + float _sun_azimuth_angle) +{ + m_sun_azimuth_angle = _sun_azimuth_angle; +} + +/*! + * @brief This function returns the value of member sun_azimuth_angle + * @return Value of member sun_azimuth_angle + */ +float carla_msgs::msg::CarlaWeatherParameters::sun_azimuth_angle() const +{ + return m_sun_azimuth_angle; +} + +/*! + * @brief This function returns a reference to member sun_azimuth_angle + * @return Reference to member sun_azimuth_angle + */ +float& carla_msgs::msg::CarlaWeatherParameters::sun_azimuth_angle() +{ + return m_sun_azimuth_angle; +} + +/*! + * @brief This function sets a value in member sun_altitude_angle + * @param _sun_altitude_angle New value for member sun_altitude_angle + */ +void carla_msgs::msg::CarlaWeatherParameters::sun_altitude_angle( + float _sun_altitude_angle) +{ + m_sun_altitude_angle = _sun_altitude_angle; +} + +/*! + * @brief This function returns the value of member sun_altitude_angle + * @return Value of member sun_altitude_angle + */ +float carla_msgs::msg::CarlaWeatherParameters::sun_altitude_angle() const +{ + return m_sun_altitude_angle; +} + +/*! + * @brief This function returns a reference to member sun_altitude_angle + * @return Reference to member sun_altitude_angle + */ +float& carla_msgs::msg::CarlaWeatherParameters::sun_altitude_angle() +{ + return m_sun_altitude_angle; +} + + +size_t carla_msgs::msg::CarlaWeatherParameters::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaWeatherParameters::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaWeatherParameters::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParameters.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParameters.h new file mode 100644 index 00000000000..fdf671a8cbf --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParameters.h @@ -0,0 +1,370 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaWeatherParameters.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWEATHERPARAMETERS_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWEATHERPARAMETERS_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CarlaWeatherParameters_SOURCE) +#define CarlaWeatherParameters_DllAPI __declspec( dllexport ) +#else +#define CarlaWeatherParameters_DllAPI __declspec( dllimport ) +#endif // CarlaWeatherParameters_SOURCE +#else +#define CarlaWeatherParameters_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CarlaWeatherParameters_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace msg { + /*! + * @brief This class represents the structure CarlaWeatherParameters defined by the user in the IDL file. + * @ingroup CARLAWEATHERPARAMETERS + */ + class CarlaWeatherParameters + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaWeatherParameters(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaWeatherParameters(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaWeatherParameters that will be copied. + */ + eProsima_user_DllExport CarlaWeatherParameters( + const CarlaWeatherParameters& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaWeatherParameters that will be copied. + */ + eProsima_user_DllExport CarlaWeatherParameters( + CarlaWeatherParameters&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaWeatherParameters that will be copied. + */ + eProsima_user_DllExport CarlaWeatherParameters& operator =( + const CarlaWeatherParameters& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaWeatherParameters that will be copied. + */ + eProsima_user_DllExport CarlaWeatherParameters& operator =( + CarlaWeatherParameters&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaWeatherParameters object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaWeatherParameters& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaWeatherParameters object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaWeatherParameters& x) const; + + /*! + * @brief This function sets a value in member cloudiness + * @param _cloudiness New value for member cloudiness + */ + eProsima_user_DllExport void cloudiness( + float _cloudiness); + + /*! + * @brief This function returns the value of member cloudiness + * @return Value of member cloudiness + */ + eProsima_user_DllExport float cloudiness() const; + + /*! + * @brief This function returns a reference to member cloudiness + * @return Reference to member cloudiness + */ + eProsima_user_DllExport float& cloudiness(); + + /*! + * @brief This function sets a value in member precipitation + * @param _precipitation New value for member precipitation + */ + eProsima_user_DllExport void precipitation( + float _precipitation); + + /*! + * @brief This function returns the value of member precipitation + * @return Value of member precipitation + */ + eProsima_user_DllExport float precipitation() const; + + /*! + * @brief This function returns a reference to member precipitation + * @return Reference to member precipitation + */ + eProsima_user_DllExport float& precipitation(); + + /*! + * @brief This function sets a value in member precipitation_deposits + * @param _precipitation_deposits New value for member precipitation_deposits + */ + eProsima_user_DllExport void precipitation_deposits( + float _precipitation_deposits); + + /*! + * @brief This function returns the value of member precipitation_deposits + * @return Value of member precipitation_deposits + */ + eProsima_user_DllExport float precipitation_deposits() const; + + /*! + * @brief This function returns a reference to member precipitation_deposits + * @return Reference to member precipitation_deposits + */ + eProsima_user_DllExport float& precipitation_deposits(); + + /*! + * @brief This function sets a value in member wind_intensity + * @param _wind_intensity New value for member wind_intensity + */ + eProsima_user_DllExport void wind_intensity( + float _wind_intensity); + + /*! + * @brief This function returns the value of member wind_intensity + * @return Value of member wind_intensity + */ + eProsima_user_DllExport float wind_intensity() const; + + /*! + * @brief This function returns a reference to member wind_intensity + * @return Reference to member wind_intensity + */ + eProsima_user_DllExport float& wind_intensity(); + + /*! + * @brief This function sets a value in member fog_density + * @param _fog_density New value for member fog_density + */ + eProsima_user_DllExport void fog_density( + float _fog_density); + + /*! + * @brief This function returns the value of member fog_density + * @return Value of member fog_density + */ + eProsima_user_DllExport float fog_density() const; + + /*! + * @brief This function returns a reference to member fog_density + * @return Reference to member fog_density + */ + eProsima_user_DllExport float& fog_density(); + + /*! + * @brief This function sets a value in member fog_distance + * @param _fog_distance New value for member fog_distance + */ + eProsima_user_DllExport void fog_distance( + float _fog_distance); + + /*! + * @brief This function returns the value of member fog_distance + * @return Value of member fog_distance + */ + eProsima_user_DllExport float fog_distance() const; + + /*! + * @brief This function returns a reference to member fog_distance + * @return Reference to member fog_distance + */ + eProsima_user_DllExport float& fog_distance(); + + /*! + * @brief This function sets a value in member wetness + * @param _wetness New value for member wetness + */ + eProsima_user_DllExport void wetness( + float _wetness); + + /*! + * @brief This function returns the value of member wetness + * @return Value of member wetness + */ + eProsima_user_DllExport float wetness() const; + + /*! + * @brief This function returns a reference to member wetness + * @return Reference to member wetness + */ + eProsima_user_DllExport float& wetness(); + + /*! + * @brief This function sets a value in member sun_azimuth_angle + * @param _sun_azimuth_angle New value for member sun_azimuth_angle + */ + eProsima_user_DllExport void sun_azimuth_angle( + float _sun_azimuth_angle); + + /*! + * @brief This function returns the value of member sun_azimuth_angle + * @return Value of member sun_azimuth_angle + */ + eProsima_user_DllExport float sun_azimuth_angle() const; + + /*! + * @brief This function returns a reference to member sun_azimuth_angle + * @return Reference to member sun_azimuth_angle + */ + eProsima_user_DllExport float& sun_azimuth_angle(); + + /*! + * @brief This function sets a value in member sun_altitude_angle + * @param _sun_altitude_angle New value for member sun_altitude_angle + */ + eProsima_user_DllExport void sun_altitude_angle( + float _sun_altitude_angle); + + /*! + * @brief This function returns the value of member sun_altitude_angle + * @return Value of member sun_altitude_angle + */ + eProsima_user_DllExport float sun_altitude_angle() const; + + /*! + * @brief This function returns a reference to member sun_altitude_angle + * @return Reference to member sun_altitude_angle + */ + eProsima_user_DllExport float& sun_altitude_angle(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::msg::CarlaWeatherParameters& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + float m_cloudiness; + float m_precipitation; + float m_precipitation_deposits; + float m_wind_intensity; + float m_fog_density; + float m_fog_distance; + float m_wetness; + float m_sun_azimuth_angle; + float m_sun_altitude_angle; + }; + } // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWEATHERPARAMETERS_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParametersPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParametersPubSubTypes.cxx new file mode 100644 index 00000000000..514e3bfc24e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParametersPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaWeatherParametersPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaWeatherParametersPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaWeatherParametersPubSubType::CarlaWeatherParametersPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaWeatherParameters_"); + auto type_size = CarlaWeatherParameters::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaWeatherParameters::isKeyDefined(); + size_t keyLength = CarlaWeatherParameters::getKeyMaxCdrSerializedSize() > 16 ? + CarlaWeatherParameters::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaWeatherParametersPubSubType::~CarlaWeatherParametersPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaWeatherParametersPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaWeatherParameters* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaWeatherParametersPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaWeatherParameters* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaWeatherParametersPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaWeatherParametersPubSubType::createData() + { + return reinterpret_cast(new CarlaWeatherParameters()); + } + + void CarlaWeatherParametersPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaWeatherParametersPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaWeatherParameters* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaWeatherParameters::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaWeatherParameters::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParametersPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParametersPubSubTypes.h new file mode 100644 index 00000000000..5bac31db030 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParametersPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaWeatherParametersPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWEATHERPARAMETERS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWEATHERPARAMETERS_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaWeatherParameters.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaWeatherParameters is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CarlaWeatherParameters defined by the user in the IDL file. + * @ingroup CARLAWEATHERPARAMETERS + */ + class CarlaWeatherParametersPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaWeatherParameters type; + + eProsima_user_DllExport CarlaWeatherParametersPubSubType(); + + eProsima_user_DllExport virtual ~CarlaWeatherParametersPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) CarlaWeatherParameters(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWEATHERPARAMETERS_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfo.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfo.cxx new file mode 100644 index 00000000000..225d74cff63 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfo.cxx @@ -0,0 +1,242 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaWorldInfo.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaWorldInfo.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::msg::CarlaWorldInfo::CarlaWorldInfo() +{ + // m_map_name com.eprosima.idl.parser.typecode.StringTypeCode@75d2da2d + m_map_name =""; + // m_opendrive com.eprosima.idl.parser.typecode.StringTypeCode@4278284b + m_opendrive =""; + +} + +carla_msgs::msg::CarlaWorldInfo::~CarlaWorldInfo() +{ + +} + +carla_msgs::msg::CarlaWorldInfo::CarlaWorldInfo( + const CarlaWorldInfo& x) +{ + m_map_name = x.m_map_name; + m_opendrive = x.m_opendrive; +} + +carla_msgs::msg::CarlaWorldInfo::CarlaWorldInfo( + CarlaWorldInfo&& x) +{ + m_map_name = std::move(x.m_map_name); + m_opendrive = std::move(x.m_opendrive); +} + +carla_msgs::msg::CarlaWorldInfo& carla_msgs::msg::CarlaWorldInfo::operator =( + const CarlaWorldInfo& x) +{ + + m_map_name = x.m_map_name; + m_opendrive = x.m_opendrive; + + return *this; +} + +carla_msgs::msg::CarlaWorldInfo& carla_msgs::msg::CarlaWorldInfo::operator =( + CarlaWorldInfo&& x) +{ + + m_map_name = std::move(x.m_map_name); + m_opendrive = std::move(x.m_opendrive); + + return *this; +} + +bool carla_msgs::msg::CarlaWorldInfo::operator ==( + const CarlaWorldInfo& x) const +{ + + return (m_map_name == x.m_map_name && m_opendrive == x.m_opendrive); +} + +bool carla_msgs::msg::CarlaWorldInfo::operator !=( + const CarlaWorldInfo& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::msg::CarlaWorldInfo::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::msg::CarlaWorldInfo::getCdrSerializedSize( + const carla_msgs::msg::CarlaWorldInfo& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.map_name().size() + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.opendrive().size() + 1; + + + return current_alignment - initial_alignment; +} + +void carla_msgs::msg::CarlaWorldInfo::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_map_name; + scdr << m_opendrive; + +} + +void carla_msgs::msg::CarlaWorldInfo::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_map_name; + dcdr >> m_opendrive; +} + +/*! + * @brief This function copies the value in member map_name + * @param _map_name New value to be copied in member map_name + */ +void carla_msgs::msg::CarlaWorldInfo::map_name( + const std::string& _map_name) +{ + m_map_name = _map_name; +} + +/*! + * @brief This function moves the value in member map_name + * @param _map_name New value to be moved in member map_name + */ +void carla_msgs::msg::CarlaWorldInfo::map_name( + std::string&& _map_name) +{ + m_map_name = std::move(_map_name); +} + +/*! + * @brief This function returns a constant reference to member map_name + * @return Constant reference to member map_name + */ +const std::string& carla_msgs::msg::CarlaWorldInfo::map_name() const +{ + return m_map_name; +} + +/*! + * @brief This function returns a reference to member map_name + * @return Reference to member map_name + */ +std::string& carla_msgs::msg::CarlaWorldInfo::map_name() +{ + return m_map_name; +} +/*! + * @brief This function copies the value in member opendrive + * @param _opendrive New value to be copied in member opendrive + */ +void carla_msgs::msg::CarlaWorldInfo::opendrive( + const std::string& _opendrive) +{ + m_opendrive = _opendrive; +} + +/*! + * @brief This function moves the value in member opendrive + * @param _opendrive New value to be moved in member opendrive + */ +void carla_msgs::msg::CarlaWorldInfo::opendrive( + std::string&& _opendrive) +{ + m_opendrive = std::move(_opendrive); +} + +/*! + * @brief This function returns a constant reference to member opendrive + * @return Constant reference to member opendrive + */ +const std::string& carla_msgs::msg::CarlaWorldInfo::opendrive() const +{ + return m_opendrive; +} + +/*! + * @brief This function returns a reference to member opendrive + * @return Reference to member opendrive + */ +std::string& carla_msgs::msg::CarlaWorldInfo::opendrive() +{ + return m_opendrive; +} + +size_t carla_msgs::msg::CarlaWorldInfo::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::msg::CarlaWorldInfo::isKeyDefined() +{ + return false; +} + +void carla_msgs::msg::CarlaWorldInfo::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfo.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfo.h new file mode 100644 index 00000000000..2bf1f07a233 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfo.h @@ -0,0 +1,242 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaWorldInfo.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWORLDINFO_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWORLDINFO_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CarlaWorldInfo_SOURCE) +#define CarlaWorldInfo_DllAPI __declspec( dllexport ) +#else +#define CarlaWorldInfo_DllAPI __declspec( dllimport ) +#endif // CarlaWorldInfo_SOURCE +#else +#define CarlaWorldInfo_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CarlaWorldInfo_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace msg { + /*! + * @brief This class represents the structure CarlaWorldInfo defined by the user in the IDL file. + * @ingroup CARLAWORLDINFO + */ + class CarlaWorldInfo + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaWorldInfo(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaWorldInfo(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaWorldInfo that will be copied. + */ + eProsima_user_DllExport CarlaWorldInfo( + const CarlaWorldInfo& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaWorldInfo that will be copied. + */ + eProsima_user_DllExport CarlaWorldInfo( + CarlaWorldInfo&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaWorldInfo that will be copied. + */ + eProsima_user_DllExport CarlaWorldInfo& operator =( + const CarlaWorldInfo& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaWorldInfo that will be copied. + */ + eProsima_user_DllExport CarlaWorldInfo& operator =( + CarlaWorldInfo&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaWorldInfo object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaWorldInfo& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaWorldInfo object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaWorldInfo& x) const; + + /*! + * @brief This function copies the value in member map_name + * @param _map_name New value to be copied in member map_name + */ + eProsima_user_DllExport void map_name( + const std::string& _map_name); + + /*! + * @brief This function moves the value in member map_name + * @param _map_name New value to be moved in member map_name + */ + eProsima_user_DllExport void map_name( + std::string&& _map_name); + + /*! + * @brief This function returns a constant reference to member map_name + * @return Constant reference to member map_name + */ + eProsima_user_DllExport const std::string& map_name() const; + + /*! + * @brief This function returns a reference to member map_name + * @return Reference to member map_name + */ + eProsima_user_DllExport std::string& map_name(); + /*! + * @brief This function copies the value in member opendrive + * @param _opendrive New value to be copied in member opendrive + */ + eProsima_user_DllExport void opendrive( + const std::string& _opendrive); + + /*! + * @brief This function moves the value in member opendrive + * @param _opendrive New value to be moved in member opendrive + */ + eProsima_user_DllExport void opendrive( + std::string&& _opendrive); + + /*! + * @brief This function returns a constant reference to member opendrive + * @return Constant reference to member opendrive + */ + eProsima_user_DllExport const std::string& opendrive() const; + + /*! + * @brief This function returns a reference to member opendrive + * @return Reference to member opendrive + */ + eProsima_user_DllExport std::string& opendrive(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::msg::CarlaWorldInfo& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std::string m_map_name; + std::string m_opendrive; + }; + } // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWORLDINFO_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfoPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfoPubSubTypes.cxx new file mode 100644 index 00000000000..5fbc333d593 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfoPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaWorldInfoPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CarlaWorldInfoPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace msg { + CarlaWorldInfoPubSubType::CarlaWorldInfoPubSubType() + { + setName("carla_msgs::msg::dds_::CarlaWorldInfo_"); + auto type_size = CarlaWorldInfo::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CarlaWorldInfo::isKeyDefined(); + size_t keyLength = CarlaWorldInfo::getKeyMaxCdrSerializedSize() > 16 ? + CarlaWorldInfo::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CarlaWorldInfoPubSubType::~CarlaWorldInfoPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CarlaWorldInfoPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CarlaWorldInfo* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CarlaWorldInfoPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CarlaWorldInfo* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CarlaWorldInfoPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CarlaWorldInfoPubSubType::createData() + { + return reinterpret_cast(new CarlaWorldInfo()); + } + + void CarlaWorldInfoPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CarlaWorldInfoPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CarlaWorldInfo* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CarlaWorldInfo::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CarlaWorldInfo::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfoPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfoPubSubTypes.h new file mode 100644 index 00000000000..4ae4a0036e8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfoPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CarlaWorldInfoPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWORLDINFO_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWORLDINFO_PUBSUBTYPES_H_ + +#include +#include + +#include "CarlaWorldInfo.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CarlaWorldInfo is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CarlaWorldInfo defined by the user in the IDL file. + * @ingroup CARLAWORLDINFO + */ + class CarlaWorldInfoPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CarlaWorldInfo type; + + eProsima_user_DllExport CarlaWorldInfoPubSubType(); + + eProsima_user_DllExport virtual ~CarlaWorldInfoPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWORLDINFO_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObject.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObject.cxx new file mode 100644 index 00000000000..dc5fa93adfc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObject.cxx @@ -0,0 +1,329 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DestroyObject.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "DestroyObject.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::srv::DestroyObject_Request::DestroyObject_Request() +{ + // m_id com.eprosima.idl.parser.typecode.PrimitiveTypeCode@32a068d1 + m_id = 0; + +} + +carla_msgs::srv::DestroyObject_Request::~DestroyObject_Request() +{ +} + +carla_msgs::srv::DestroyObject_Request::DestroyObject_Request( + const DestroyObject_Request& x) +{ + m_id = x.m_id; +} + +carla_msgs::srv::DestroyObject_Request::DestroyObject_Request( + DestroyObject_Request&& x) +{ + m_id = x.m_id; +} + +carla_msgs::srv::DestroyObject_Request& carla_msgs::srv::DestroyObject_Request::operator =( + const DestroyObject_Request& x) +{ + + m_id = x.m_id; + + return *this; +} + +carla_msgs::srv::DestroyObject_Request& carla_msgs::srv::DestroyObject_Request::operator =( + DestroyObject_Request&& x) +{ + + m_id = x.m_id; + + return *this; +} + +bool carla_msgs::srv::DestroyObject_Request::operator ==( + const DestroyObject_Request& x) const +{ + + return (m_id == x.m_id); +} + +bool carla_msgs::srv::DestroyObject_Request::operator !=( + const DestroyObject_Request& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::srv::DestroyObject_Request::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::srv::DestroyObject_Request::getCdrSerializedSize( + const carla_msgs::srv::DestroyObject_Request& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + return current_alignment - initial_alignment; +} + +void carla_msgs::srv::DestroyObject_Request::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_id; + +} + +void carla_msgs::srv::DestroyObject_Request::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_id; +} + +/*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ +void carla_msgs::srv::DestroyObject_Request::id( + int32_t _id) +{ + m_id = _id; +} + +/*! + * @brief This function returns the value of member id + * @return Value of member id + */ +int32_t carla_msgs::srv::DestroyObject_Request::id() const +{ + return m_id; +} + +/*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ +int32_t& carla_msgs::srv::DestroyObject_Request::id() +{ + return m_id; +} + + +size_t carla_msgs::srv::DestroyObject_Request::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::srv::DestroyObject_Request::isKeyDefined() +{ + return false; +} + +void carla_msgs::srv::DestroyObject_Request::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + +carla_msgs::srv::DestroyObject_Response::DestroyObject_Response() +{ + // m_success com.eprosima.idl.parser.typecode.PrimitiveTypeCode@62fdb4a6 + m_success = false; + +} + +carla_msgs::srv::DestroyObject_Response::~DestroyObject_Response() +{ +} + +carla_msgs::srv::DestroyObject_Response::DestroyObject_Response( + const DestroyObject_Response& x) +{ + m_success = x.m_success; +} + +carla_msgs::srv::DestroyObject_Response::DestroyObject_Response( + DestroyObject_Response&& x) +{ + m_success = x.m_success; +} + +carla_msgs::srv::DestroyObject_Response& carla_msgs::srv::DestroyObject_Response::operator =( + const DestroyObject_Response& x) +{ + + m_success = x.m_success; + + return *this; +} + +carla_msgs::srv::DestroyObject_Response& carla_msgs::srv::DestroyObject_Response::operator =( + DestroyObject_Response&& x) +{ + + m_success = x.m_success; + + return *this; +} + +bool carla_msgs::srv::DestroyObject_Response::operator ==( + const DestroyObject_Response& x) const +{ + + return (m_success == x.m_success); +} + +bool carla_msgs::srv::DestroyObject_Response::operator !=( + const DestroyObject_Response& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::srv::DestroyObject_Response::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::srv::DestroyObject_Response::getCdrSerializedSize( + const carla_msgs::srv::DestroyObject_Response& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void carla_msgs::srv::DestroyObject_Response::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_success; + +} + +void carla_msgs::srv::DestroyObject_Response::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_success; +} + +/*! + * @brief This function sets a value in member success + * @param _success New value for member success + */ +void carla_msgs::srv::DestroyObject_Response::success( + bool _success) +{ + m_success = _success; +} + +/*! + * @brief This function returns the value of member success + * @return Value of member success + */ +bool carla_msgs::srv::DestroyObject_Response::success() const +{ + return m_success; +} + +/*! + * @brief This function returns a reference to member success + * @return Reference to member success + */ +bool& carla_msgs::srv::DestroyObject_Response::success() +{ + return m_success; +} + + +size_t carla_msgs::srv::DestroyObject_Response::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::srv::DestroyObject_Response::isKeyDefined() +{ + return false; +} + +void carla_msgs::srv::DestroyObject_Response::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObject.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObject.h new file mode 100644 index 00000000000..f505e6a1f17 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObject.h @@ -0,0 +1,351 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DestroyObject.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_DESTROYOBJECT_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_DESTROYOBJECT_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(DestroyObject_SOURCE) +#define DestroyObject_DllAPI __declspec( dllexport ) +#else +#define DestroyObject_DllAPI __declspec( dllimport ) +#endif // DestroyObject_SOURCE +#else +#define DestroyObject_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define DestroyObject_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace srv { + /*! + * @brief This class represents the structure DestroyObject_Request defined by the user in the IDL file. + * @ingroup DESTROYOBJECT + */ + class DestroyObject_Request + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport DestroyObject_Request(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~DestroyObject_Request(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::srv::DestroyObject_Request that will be copied. + */ + eProsima_user_DllExport DestroyObject_Request( + const DestroyObject_Request& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::srv::DestroyObject_Request that will be copied. + */ + eProsima_user_DllExport DestroyObject_Request( + DestroyObject_Request&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::srv::DestroyObject_Request that will be copied. + */ + eProsima_user_DllExport DestroyObject_Request& operator =( + const DestroyObject_Request& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::srv::DestroyObject_Request that will be copied. + */ + eProsima_user_DllExport DestroyObject_Request& operator =( + DestroyObject_Request&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::DestroyObject_Request object to compare. + */ + eProsima_user_DllExport bool operator ==( + const DestroyObject_Request& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::DestroyObject_Request object to compare. + */ + eProsima_user_DllExport bool operator !=( + const DestroyObject_Request& x) const; + + /*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ + eProsima_user_DllExport void id( + int32_t _id); + + /*! + * @brief This function returns the value of member id + * @return Value of member id + */ + eProsima_user_DllExport int32_t id() const; + + /*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ + eProsima_user_DllExport int32_t& id(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::srv::DestroyObject_Request& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + int32_t m_id; + }; + /*! + * @brief This class represents the structure DestroyObject_Response defined by the user in the IDL file. + * @ingroup DESTROYOBJECT + */ + class DestroyObject_Response + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport DestroyObject_Response(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~DestroyObject_Response(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::srv::DestroyObject_Response that will be copied. + */ + eProsima_user_DllExport DestroyObject_Response( + const DestroyObject_Response& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::srv::DestroyObject_Response that will be copied. + */ + eProsima_user_DllExport DestroyObject_Response( + DestroyObject_Response&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::srv::DestroyObject_Response that will be copied. + */ + eProsima_user_DllExport DestroyObject_Response& operator =( + const DestroyObject_Response& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::srv::DestroyObject_Response that will be copied. + */ + eProsima_user_DllExport DestroyObject_Response& operator =( + DestroyObject_Response&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::DestroyObject_Response object to compare. + */ + eProsima_user_DllExport bool operator ==( + const DestroyObject_Response& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::DestroyObject_Response object to compare. + */ + eProsima_user_DllExport bool operator !=( + const DestroyObject_Response& x) const; + + /*! + * @brief This function sets a value in member success + * @param _success New value for member success + */ + eProsima_user_DllExport void success( + bool _success); + + /*! + * @brief This function returns the value of member success + * @return Value of member success + */ + eProsima_user_DllExport bool success() const; + + /*! + * @brief This function returns a reference to member success + * @return Reference to member success + */ + eProsima_user_DllExport bool& success(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::srv::DestroyObject_Response& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + bool m_success; + }; + } // namespace srv +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_DESTROYOBJECT_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObjectPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObjectPubSubTypes.cxx new file mode 100644 index 00000000000..0b32cd6ee2f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObjectPubSubTypes.cxx @@ -0,0 +1,316 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DestroyObjectPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "DestroyObjectPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace srv { + DestroyObject_RequestPubSubType::DestroyObject_RequestPubSubType() + { + setName("carla_msgs::srv::dds_::DestroyObject_Request_"); + auto type_size = DestroyObject_Request::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = DestroyObject_Request::isKeyDefined(); + size_t keyLength = DestroyObject_Request::getKeyMaxCdrSerializedSize() > 16 ? + DestroyObject_Request::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + DestroyObject_RequestPubSubType::~DestroyObject_RequestPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool DestroyObject_RequestPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + DestroyObject_Request* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool DestroyObject_RequestPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + DestroyObject_Request* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function DestroyObject_RequestPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* DestroyObject_RequestPubSubType::createData() + { + return reinterpret_cast(new DestroyObject_Request()); + } + + void DestroyObject_RequestPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool DestroyObject_RequestPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + DestroyObject_Request* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + DestroyObject_Request::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || DestroyObject_Request::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + DestroyObject_ResponsePubSubType::DestroyObject_ResponsePubSubType() + { + setName("carla_msgs::srv::dds_::DestroyObject_Response_"); + auto type_size = DestroyObject_Response::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = DestroyObject_Response::isKeyDefined(); + size_t keyLength = DestroyObject_Response::getKeyMaxCdrSerializedSize() > 16 ? + DestroyObject_Response::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + DestroyObject_ResponsePubSubType::~DestroyObject_ResponsePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool DestroyObject_ResponsePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + DestroyObject_Response* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool DestroyObject_ResponsePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + DestroyObject_Response* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function DestroyObject_ResponsePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* DestroyObject_ResponsePubSubType::createData() + { + return reinterpret_cast(new DestroyObject_Response()); + } + + void DestroyObject_ResponsePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool DestroyObject_ResponsePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + DestroyObject_Response* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + DestroyObject_Response::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || DestroyObject_Response::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace srv + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObjectPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObjectPubSubTypes.h new file mode 100644 index 00000000000..06d7a601072 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObjectPubSubTypes.h @@ -0,0 +1,171 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DestroyObjectPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_DESTROYOBJECT_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_DESTROYOBJECT_PUBSUBTYPES_H_ + +#include +#include + +#include "DestroyObject.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated DestroyObject is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace srv + { + /*! + * @brief This class represents the TopicDataType of the type DestroyObject_Request defined by the user in the IDL file. + * @ingroup DESTROYOBJECT + */ + class DestroyObject_RequestPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef DestroyObject_Request type; + + eProsima_user_DllExport DestroyObject_RequestPubSubType(); + + eProsima_user_DllExport virtual ~DestroyObject_RequestPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) DestroyObject_Request(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + /*! + * @brief This class represents the TopicDataType of the type DestroyObject_Response defined by the user in the IDL file. + * @ingroup DESTROYOBJECT + */ + class DestroyObject_ResponsePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef DestroyObject_Response type; + + eProsima_user_DllExport DestroyObject_ResponsePubSubType(); + + eProsima_user_DllExport virtual ~DestroyObject_ResponsePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) DestroyObject_Response(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_DESTROYOBJECT_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMaps.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMaps.cxx new file mode 100644 index 00000000000..86a1288538a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMaps.cxx @@ -0,0 +1,344 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file GetAvailableMaps.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "GetAvailableMaps.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::srv::GetAvailableMaps_Request::GetAvailableMaps_Request() +{ + // m_structure_needs_at_least_one_member com.eprosima.idl.parser.typecode.PrimitiveTypeCode@70b0b186 + m_structure_needs_at_least_one_member = 0; + +} + +carla_msgs::srv::GetAvailableMaps_Request::~GetAvailableMaps_Request() +{ +} + +carla_msgs::srv::GetAvailableMaps_Request::GetAvailableMaps_Request( + const GetAvailableMaps_Request& x) +{ + m_structure_needs_at_least_one_member = x.m_structure_needs_at_least_one_member; +} + +carla_msgs::srv::GetAvailableMaps_Request::GetAvailableMaps_Request( + GetAvailableMaps_Request&& x) +{ + m_structure_needs_at_least_one_member = x.m_structure_needs_at_least_one_member; +} + +carla_msgs::srv::GetAvailableMaps_Request& carla_msgs::srv::GetAvailableMaps_Request::operator =( + const GetAvailableMaps_Request& x) +{ + + m_structure_needs_at_least_one_member = x.m_structure_needs_at_least_one_member; + + return *this; +} + +carla_msgs::srv::GetAvailableMaps_Request& carla_msgs::srv::GetAvailableMaps_Request::operator =( + GetAvailableMaps_Request&& x) +{ + + m_structure_needs_at_least_one_member = x.m_structure_needs_at_least_one_member; + + return *this; +} + +bool carla_msgs::srv::GetAvailableMaps_Request::operator ==( + const GetAvailableMaps_Request& x) const +{ + + return (m_structure_needs_at_least_one_member == x.m_structure_needs_at_least_one_member); +} + +bool carla_msgs::srv::GetAvailableMaps_Request::operator !=( + const GetAvailableMaps_Request& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::srv::GetAvailableMaps_Request::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::srv::GetAvailableMaps_Request::getCdrSerializedSize( + const carla_msgs::srv::GetAvailableMaps_Request& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void carla_msgs::srv::GetAvailableMaps_Request::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_structure_needs_at_least_one_member; + +} + +void carla_msgs::srv::GetAvailableMaps_Request::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_structure_needs_at_least_one_member; +} + +/*! + * @brief This function sets a value in member structure_needs_at_least_one_member + * @param _structure_needs_at_least_one_member New value for member structure_needs_at_least_one_member + */ +void carla_msgs::srv::GetAvailableMaps_Request::structure_needs_at_least_one_member( + uint8_t _structure_needs_at_least_one_member) +{ + m_structure_needs_at_least_one_member = _structure_needs_at_least_one_member; +} + +/*! + * @brief This function returns the value of member structure_needs_at_least_one_member + * @return Value of member structure_needs_at_least_one_member + */ +uint8_t carla_msgs::srv::GetAvailableMaps_Request::structure_needs_at_least_one_member() const +{ + return m_structure_needs_at_least_one_member; +} + +/*! + * @brief This function returns a reference to member structure_needs_at_least_one_member + * @return Reference to member structure_needs_at_least_one_member + */ +uint8_t& carla_msgs::srv::GetAvailableMaps_Request::structure_needs_at_least_one_member() +{ + return m_structure_needs_at_least_one_member; +} + + +size_t carla_msgs::srv::GetAvailableMaps_Request::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::srv::GetAvailableMaps_Request::isKeyDefined() +{ + return false; +} + +void carla_msgs::srv::GetAvailableMaps_Request::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + +carla_msgs::srv::GetAvailableMaps_Response::GetAvailableMaps_Response() +{ + // m_maps com.eprosima.idl.parser.typecode.SequenceTypeCode@1e67a849 + + +} + +carla_msgs::srv::GetAvailableMaps_Response::~GetAvailableMaps_Response() +{ +} + +carla_msgs::srv::GetAvailableMaps_Response::GetAvailableMaps_Response( + const GetAvailableMaps_Response& x) +{ + m_maps = x.m_maps; +} + +carla_msgs::srv::GetAvailableMaps_Response::GetAvailableMaps_Response( + GetAvailableMaps_Response&& x) +{ + m_maps = std::move(x.m_maps); +} + +carla_msgs::srv::GetAvailableMaps_Response& carla_msgs::srv::GetAvailableMaps_Response::operator =( + const GetAvailableMaps_Response& x) +{ + + m_maps = x.m_maps; + + return *this; +} + +carla_msgs::srv::GetAvailableMaps_Response& carla_msgs::srv::GetAvailableMaps_Response::operator =( + GetAvailableMaps_Response&& x) +{ + + m_maps = std::move(x.m_maps); + + return *this; +} + +bool carla_msgs::srv::GetAvailableMaps_Response::operator ==( + const GetAvailableMaps_Response& x) const +{ + + return (m_maps == x.m_maps); +} + +bool carla_msgs::srv::GetAvailableMaps_Response::operator !=( + const GetAvailableMaps_Response& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::srv::GetAvailableMaps_Response::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < 100; ++a) + { + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + } + return current_alignment - initial_alignment; +} + +size_t carla_msgs::srv::GetAvailableMaps_Response::getCdrSerializedSize( + const carla_msgs::srv::GetAvailableMaps_Response& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < data.maps().size(); ++a) + { + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + + data.maps().at(a).size() + 1; + } + return current_alignment - initial_alignment; +} + +void carla_msgs::srv::GetAvailableMaps_Response::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_maps;} + +void carla_msgs::srv::GetAvailableMaps_Response::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_maps;} + +/*! + * @brief This function copies the value in member maps + * @param _maps New value to be copied in member maps + */ +void carla_msgs::srv::GetAvailableMaps_Response::maps( + const std::vector& _maps) +{ + m_maps = _maps; +} + +/*! + * @brief This function moves the value in member maps + * @param _maps New value to be moved in member maps + */ +void carla_msgs::srv::GetAvailableMaps_Response::maps( + std::vector&& _maps) +{ + m_maps = std::move(_maps); +} + +/*! + * @brief This function returns a constant reference to member maps + * @return Constant reference to member maps + */ +const std::vector& carla_msgs::srv::GetAvailableMaps_Response::maps() const +{ + return m_maps; +} + +/*! + * @brief This function returns a reference to member maps + * @return Reference to member maps + */ +std::vector& carla_msgs::srv::GetAvailableMaps_Response::maps() +{ + return m_maps; +} + +size_t carla_msgs::srv::GetAvailableMaps_Response::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::srv::GetAvailableMaps_Response::isKeyDefined() +{ + return false; +} + +void carla_msgs::srv::GetAvailableMaps_Response::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMaps.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMaps.h new file mode 100644 index 00000000000..a58220f60c4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMaps.h @@ -0,0 +1,357 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file GetAvailableMaps.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETAVAILABLEMAPS_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETAVAILABLEMAPS_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(GetAvailableMaps_SOURCE) +#define GetAvailableMaps_DllAPI __declspec( dllexport ) +#else +#define GetAvailableMaps_DllAPI __declspec( dllimport ) +#endif // GetAvailableMaps_SOURCE +#else +#define GetAvailableMaps_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define GetAvailableMaps_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace srv { + /*! + * @brief This class represents the structure GetAvailableMaps_Request defined by the user in the IDL file. + * @ingroup GETAVAILABLEMAPS + */ + class GetAvailableMaps_Request + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport GetAvailableMaps_Request(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~GetAvailableMaps_Request(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::srv::GetAvailableMaps_Request that will be copied. + */ + eProsima_user_DllExport GetAvailableMaps_Request( + const GetAvailableMaps_Request& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::srv::GetAvailableMaps_Request that will be copied. + */ + eProsima_user_DllExport GetAvailableMaps_Request( + GetAvailableMaps_Request&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::srv::GetAvailableMaps_Request that will be copied. + */ + eProsima_user_DllExport GetAvailableMaps_Request& operator =( + const GetAvailableMaps_Request& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::srv::GetAvailableMaps_Request that will be copied. + */ + eProsima_user_DllExport GetAvailableMaps_Request& operator =( + GetAvailableMaps_Request&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::GetAvailableMaps_Request object to compare. + */ + eProsima_user_DllExport bool operator ==( + const GetAvailableMaps_Request& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::GetAvailableMaps_Request object to compare. + */ + eProsima_user_DllExport bool operator !=( + const GetAvailableMaps_Request& x) const; + + /*! + * @brief This function sets a value in member structure_needs_at_least_one_member + * @param _structure_needs_at_least_one_member New value for member structure_needs_at_least_one_member + */ + eProsima_user_DllExport void structure_needs_at_least_one_member( + uint8_t _structure_needs_at_least_one_member); + + /*! + * @brief This function returns the value of member structure_needs_at_least_one_member + * @return Value of member structure_needs_at_least_one_member + */ + eProsima_user_DllExport uint8_t structure_needs_at_least_one_member() const; + + /*! + * @brief This function returns a reference to member structure_needs_at_least_one_member + * @return Reference to member structure_needs_at_least_one_member + */ + eProsima_user_DllExport uint8_t& structure_needs_at_least_one_member(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::srv::GetAvailableMaps_Request& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_structure_needs_at_least_one_member; + }; + /*! + * @brief This class represents the structure GetAvailableMaps_Response defined by the user in the IDL file. + * @ingroup GETAVAILABLEMAPS + */ + class GetAvailableMaps_Response + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport GetAvailableMaps_Response(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~GetAvailableMaps_Response(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::srv::GetAvailableMaps_Response that will be copied. + */ + eProsima_user_DllExport GetAvailableMaps_Response( + const GetAvailableMaps_Response& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::srv::GetAvailableMaps_Response that will be copied. + */ + eProsima_user_DllExport GetAvailableMaps_Response( + GetAvailableMaps_Response&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::srv::GetAvailableMaps_Response that will be copied. + */ + eProsima_user_DllExport GetAvailableMaps_Response& operator =( + const GetAvailableMaps_Response& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::srv::GetAvailableMaps_Response that will be copied. + */ + eProsima_user_DllExport GetAvailableMaps_Response& operator =( + GetAvailableMaps_Response&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::GetAvailableMaps_Response object to compare. + */ + eProsima_user_DllExport bool operator ==( + const GetAvailableMaps_Response& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::GetAvailableMaps_Response object to compare. + */ + eProsima_user_DllExport bool operator !=( + const GetAvailableMaps_Response& x) const; + + /*! + * @brief This function copies the value in member maps + * @param _maps New value to be copied in member maps + */ + eProsima_user_DllExport void maps( + const std::vector& _maps); + + /*! + * @brief This function moves the value in member maps + * @param _maps New value to be moved in member maps + */ + eProsima_user_DllExport void maps( + std::vector&& _maps); + + /*! + * @brief This function returns a constant reference to member maps + * @return Constant reference to member maps + */ + eProsima_user_DllExport const std::vector& maps() const; + + /*! + * @brief This function returns a reference to member maps + * @return Reference to member maps + */ + eProsima_user_DllExport std::vector& maps(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::srv::GetAvailableMaps_Response& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std::vector m_maps; + }; + } // namespace srv +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETAVAILABLEMAPS_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMapsPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMapsPubSubTypes.cxx new file mode 100644 index 00000000000..dc46fb0e1a3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMapsPubSubTypes.cxx @@ -0,0 +1,316 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file GetAvailableMapsPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "GetAvailableMapsPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace srv { + GetAvailableMaps_RequestPubSubType::GetAvailableMaps_RequestPubSubType() + { + setName("carla_msgs::srv::dds_::GetAvailableMaps_Request_"); + auto type_size = GetAvailableMaps_Request::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = GetAvailableMaps_Request::isKeyDefined(); + size_t keyLength = GetAvailableMaps_Request::getKeyMaxCdrSerializedSize() > 16 ? + GetAvailableMaps_Request::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + GetAvailableMaps_RequestPubSubType::~GetAvailableMaps_RequestPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool GetAvailableMaps_RequestPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + GetAvailableMaps_Request* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool GetAvailableMaps_RequestPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + GetAvailableMaps_Request* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function GetAvailableMaps_RequestPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* GetAvailableMaps_RequestPubSubType::createData() + { + return reinterpret_cast(new GetAvailableMaps_Request()); + } + + void GetAvailableMaps_RequestPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool GetAvailableMaps_RequestPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + GetAvailableMaps_Request* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + GetAvailableMaps_Request::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || GetAvailableMaps_Request::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + GetAvailableMaps_ResponsePubSubType::GetAvailableMaps_ResponsePubSubType() + { + setName("carla_msgs::srv::dds_::GetAvailableMaps_Response_"); + auto type_size = GetAvailableMaps_Response::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = GetAvailableMaps_Response::isKeyDefined(); + size_t keyLength = GetAvailableMaps_Response::getKeyMaxCdrSerializedSize() > 16 ? + GetAvailableMaps_Response::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + GetAvailableMaps_ResponsePubSubType::~GetAvailableMaps_ResponsePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool GetAvailableMaps_ResponsePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + GetAvailableMaps_Response* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool GetAvailableMaps_ResponsePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + GetAvailableMaps_Response* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function GetAvailableMaps_ResponsePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* GetAvailableMaps_ResponsePubSubType::createData() + { + return reinterpret_cast(new GetAvailableMaps_Response()); + } + + void GetAvailableMaps_ResponsePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool GetAvailableMaps_ResponsePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + GetAvailableMaps_Response* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + GetAvailableMaps_Response::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || GetAvailableMaps_Response::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace srv + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMapsPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMapsPubSubTypes.h new file mode 100644 index 00000000000..d9da4b72170 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMapsPubSubTypes.h @@ -0,0 +1,171 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file GetAvailableMapsPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETAVAILABLEMAPS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETAVAILABLEMAPS_PUBSUBTYPES_H_ + +#include +#include + +#include "GetAvailableMaps.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated GetAvailableMaps is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace srv + { + /*! + * @brief This class represents the TopicDataType of the type GetAvailableMaps_Request defined by the user in the IDL file. + * @ingroup GETAVAILABLEMAPS + */ + class GetAvailableMaps_RequestPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef GetAvailableMaps_Request type; + + eProsima_user_DllExport GetAvailableMaps_RequestPubSubType(); + + eProsima_user_DllExport virtual ~GetAvailableMaps_RequestPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) GetAvailableMaps_Request(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + /*! + * @brief This class represents the TopicDataType of the type GetAvailableMaps_Response defined by the user in the IDL file. + * @ingroup GETAVAILABLEMAPS + */ + class GetAvailableMaps_ResponsePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef GetAvailableMaps_Response type; + + eProsima_user_DllExport GetAvailableMaps_ResponsePubSubType(); + + eProsima_user_DllExport virtual ~GetAvailableMaps_ResponsePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETAVAILABLEMAPS_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprints.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprints.cxx new file mode 100644 index 00000000000..8110bf119b9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprints.cxx @@ -0,0 +1,351 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file GetBlueprints.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "GetBlueprints.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::srv::GetBlueprints_Request::GetBlueprints_Request() +{ + // m_filter com.eprosima.idl.parser.typecode.StringTypeCode@7c417213 + m_filter =""; + +} + +carla_msgs::srv::GetBlueprints_Request::~GetBlueprints_Request() +{ +} + +carla_msgs::srv::GetBlueprints_Request::GetBlueprints_Request( + const GetBlueprints_Request& x) +{ + m_filter = x.m_filter; +} + +carla_msgs::srv::GetBlueprints_Request::GetBlueprints_Request( + GetBlueprints_Request&& x) +{ + m_filter = std::move(x.m_filter); +} + +carla_msgs::srv::GetBlueprints_Request& carla_msgs::srv::GetBlueprints_Request::operator =( + const GetBlueprints_Request& x) +{ + + m_filter = x.m_filter; + + return *this; +} + +carla_msgs::srv::GetBlueprints_Request& carla_msgs::srv::GetBlueprints_Request::operator =( + GetBlueprints_Request&& x) +{ + + m_filter = std::move(x.m_filter); + + return *this; +} + +bool carla_msgs::srv::GetBlueprints_Request::operator ==( + const GetBlueprints_Request& x) const +{ + + return (m_filter == x.m_filter); +} + +bool carla_msgs::srv::GetBlueprints_Request::operator !=( + const GetBlueprints_Request& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::srv::GetBlueprints_Request::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::srv::GetBlueprints_Request::getCdrSerializedSize( + const carla_msgs::srv::GetBlueprints_Request& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.filter().size() + 1; + + return current_alignment - initial_alignment; +} + +void carla_msgs::srv::GetBlueprints_Request::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_filter; + +} + +void carla_msgs::srv::GetBlueprints_Request::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_filter; +} + +/*! + * @brief This function copies the value in member filter + * @param _filter New value to be copied in member filter + */ +void carla_msgs::srv::GetBlueprints_Request::filter( + const std::string& _filter) +{ + m_filter = _filter; +} + +/*! + * @brief This function moves the value in member filter + * @param _filter New value to be moved in member filter + */ +void carla_msgs::srv::GetBlueprints_Request::filter( + std::string&& _filter) +{ + m_filter = std::move(_filter); +} + +/*! + * @brief This function returns a constant reference to member filter + * @return Constant reference to member filter + */ +const std::string& carla_msgs::srv::GetBlueprints_Request::filter() const +{ + return m_filter; +} + +/*! + * @brief This function returns a reference to member filter + * @return Reference to member filter + */ +std::string& carla_msgs::srv::GetBlueprints_Request::filter() +{ + return m_filter; +} + +size_t carla_msgs::srv::GetBlueprints_Request::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::srv::GetBlueprints_Request::isKeyDefined() +{ + return false; +} + +void carla_msgs::srv::GetBlueprints_Request::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + +carla_msgs::srv::GetBlueprints_Response::GetBlueprints_Response() +{ + // m_blueprints com.eprosima.idl.parser.typecode.SequenceTypeCode@5e4c8041 + + +} + +carla_msgs::srv::GetBlueprints_Response::~GetBlueprints_Response() +{ +} + +carla_msgs::srv::GetBlueprints_Response::GetBlueprints_Response( + const GetBlueprints_Response& x) +{ + m_blueprints = x.m_blueprints; +} + +carla_msgs::srv::GetBlueprints_Response::GetBlueprints_Response( + GetBlueprints_Response&& x) +{ + m_blueprints = std::move(x.m_blueprints); +} + +carla_msgs::srv::GetBlueprints_Response& carla_msgs::srv::GetBlueprints_Response::operator =( + const GetBlueprints_Response& x) +{ + + m_blueprints = x.m_blueprints; + + return *this; +} + +carla_msgs::srv::GetBlueprints_Response& carla_msgs::srv::GetBlueprints_Response::operator =( + GetBlueprints_Response&& x) +{ + + m_blueprints = std::move(x.m_blueprints); + + return *this; +} + +bool carla_msgs::srv::GetBlueprints_Response::operator ==( + const GetBlueprints_Response& x) const +{ + + return (m_blueprints == x.m_blueprints); +} + +bool carla_msgs::srv::GetBlueprints_Response::operator !=( + const GetBlueprints_Response& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::srv::GetBlueprints_Response::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < 100; ++a) + { + current_alignment += carla_msgs::msg::CarlaActorBlueprint::getMaxCdrSerializedSize(current_alignment);} + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::srv::GetBlueprints_Response::getCdrSerializedSize( + const carla_msgs::srv::GetBlueprints_Response& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < data.blueprints().size(); ++a) + { + current_alignment += carla_msgs::msg::CarlaActorBlueprint::getCdrSerializedSize(data.blueprints().at(a), current_alignment);} + + return current_alignment - initial_alignment; +} + +void carla_msgs::srv::GetBlueprints_Response::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_blueprints; +} + +void carla_msgs::srv::GetBlueprints_Response::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_blueprints;} + +/*! + * @brief This function copies the value in member blueprints + * @param _blueprints New value to be copied in member blueprints + */ +void carla_msgs::srv::GetBlueprints_Response::blueprints( + const std::vector& _blueprints) +{ + m_blueprints = _blueprints; +} + +/*! + * @brief This function moves the value in member blueprints + * @param _blueprints New value to be moved in member blueprints + */ +void carla_msgs::srv::GetBlueprints_Response::blueprints( + std::vector&& _blueprints) +{ + m_blueprints = std::move(_blueprints); +} + +/*! + * @brief This function returns a constant reference to member blueprints + * @return Constant reference to member blueprints + */ +const std::vector& carla_msgs::srv::GetBlueprints_Response::blueprints() const +{ + return m_blueprints; +} + +/*! + * @brief This function returns a reference to member blueprints + * @return Reference to member blueprints + */ +std::vector& carla_msgs::srv::GetBlueprints_Response::blueprints() +{ + return m_blueprints; +} + +size_t carla_msgs::srv::GetBlueprints_Response::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::srv::GetBlueprints_Response::isKeyDefined() +{ + return false; +} + +void carla_msgs::srv::GetBlueprints_Response::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprints.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprints.h new file mode 100644 index 00000000000..548a7b44cf1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprints.h @@ -0,0 +1,364 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file GetBlueprints.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETBLUEPRINTS_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETBLUEPRINTS_H_ + +#include "carla_msgs/msg/CarlaActorBlueprint.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(GetBlueprints_SOURCE) +#define GetBlueprints_DllAPI __declspec( dllexport ) +#else +#define GetBlueprints_DllAPI __declspec( dllimport ) +#endif // GetBlueprints_SOURCE +#else +#define GetBlueprints_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define GetBlueprints_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace srv { + /*! + * @brief This class represents the structure GetBlueprints_Request defined by the user in the IDL file. + * @ingroup GETBLUEPRINTS + */ + class GetBlueprints_Request + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport GetBlueprints_Request(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~GetBlueprints_Request(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::srv::GetBlueprints_Request that will be copied. + */ + eProsima_user_DllExport GetBlueprints_Request( + const GetBlueprints_Request& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::srv::GetBlueprints_Request that will be copied. + */ + eProsima_user_DllExport GetBlueprints_Request( + GetBlueprints_Request&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::srv::GetBlueprints_Request that will be copied. + */ + eProsima_user_DllExport GetBlueprints_Request& operator =( + const GetBlueprints_Request& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::srv::GetBlueprints_Request that will be copied. + */ + eProsima_user_DllExport GetBlueprints_Request& operator =( + GetBlueprints_Request&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::GetBlueprints_Request object to compare. + */ + eProsima_user_DllExport bool operator ==( + const GetBlueprints_Request& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::GetBlueprints_Request object to compare. + */ + eProsima_user_DllExport bool operator !=( + const GetBlueprints_Request& x) const; + + /*! + * @brief This function copies the value in member filter + * @param _filter New value to be copied in member filter + */ + eProsima_user_DllExport void filter( + const std::string& _filter); + + /*! + * @brief This function moves the value in member filter + * @param _filter New value to be moved in member filter + */ + eProsima_user_DllExport void filter( + std::string&& _filter); + + /*! + * @brief This function returns a constant reference to member filter + * @return Constant reference to member filter + */ + eProsima_user_DllExport const std::string& filter() const; + + /*! + * @brief This function returns a reference to member filter + * @return Reference to member filter + */ + eProsima_user_DllExport std::string& filter(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::srv::GetBlueprints_Request& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std::string m_filter; + }; + /*! + * @brief This class represents the structure GetBlueprints_Response defined by the user in the IDL file. + * @ingroup GETBLUEPRINTS + */ + class GetBlueprints_Response + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport GetBlueprints_Response(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~GetBlueprints_Response(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::srv::GetBlueprints_Response that will be copied. + */ + eProsima_user_DllExport GetBlueprints_Response( + const GetBlueprints_Response& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::srv::GetBlueprints_Response that will be copied. + */ + eProsima_user_DllExport GetBlueprints_Response( + GetBlueprints_Response&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::srv::GetBlueprints_Response that will be copied. + */ + eProsima_user_DllExport GetBlueprints_Response& operator =( + const GetBlueprints_Response& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::srv::GetBlueprints_Response that will be copied. + */ + eProsima_user_DllExport GetBlueprints_Response& operator =( + GetBlueprints_Response&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::GetBlueprints_Response object to compare. + */ + eProsima_user_DllExport bool operator ==( + const GetBlueprints_Response& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::GetBlueprints_Response object to compare. + */ + eProsima_user_DllExport bool operator !=( + const GetBlueprints_Response& x) const; + + /*! + * @brief This function copies the value in member blueprints + * @param _blueprints New value to be copied in member blueprints + */ + eProsima_user_DllExport void blueprints( + const std::vector& _blueprints); + + /*! + * @brief This function moves the value in member blueprints + * @param _blueprints New value to be moved in member blueprints + */ + eProsima_user_DllExport void blueprints( + std::vector&& _blueprints); + + /*! + * @brief This function returns a constant reference to member blueprints + * @return Constant reference to member blueprints + */ + eProsima_user_DllExport const std::vector& blueprints() const; + + /*! + * @brief This function returns a reference to member blueprints + * @return Reference to member blueprints + */ + eProsima_user_DllExport std::vector& blueprints(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::srv::GetBlueprints_Response& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std::vector m_blueprints; + }; + } // namespace srv +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETBLUEPRINTS_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprintsPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprintsPubSubTypes.cxx new file mode 100644 index 00000000000..5c0b0f12ec1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprintsPubSubTypes.cxx @@ -0,0 +1,316 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file GetBlueprintsPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "GetBlueprintsPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace srv { + GetBlueprints_RequestPubSubType::GetBlueprints_RequestPubSubType() + { + setName("carla_msgs::srv::dds_::GetBlueprints_Request_"); + auto type_size = GetBlueprints_Request::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = GetBlueprints_Request::isKeyDefined(); + size_t keyLength = GetBlueprints_Request::getKeyMaxCdrSerializedSize() > 16 ? + GetBlueprints_Request::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + GetBlueprints_RequestPubSubType::~GetBlueprints_RequestPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool GetBlueprints_RequestPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + GetBlueprints_Request* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool GetBlueprints_RequestPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + GetBlueprints_Request* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function GetBlueprints_RequestPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* GetBlueprints_RequestPubSubType::createData() + { + return reinterpret_cast(new GetBlueprints_Request()); + } + + void GetBlueprints_RequestPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool GetBlueprints_RequestPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + GetBlueprints_Request* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + GetBlueprints_Request::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || GetBlueprints_Request::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + GetBlueprints_ResponsePubSubType::GetBlueprints_ResponsePubSubType() + { + setName("carla_msgs::srv::dds_::GetBlueprints_Response_"); + auto type_size = GetBlueprints_Response::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = GetBlueprints_Response::isKeyDefined(); + size_t keyLength = GetBlueprints_Response::getKeyMaxCdrSerializedSize() > 16 ? + GetBlueprints_Response::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + GetBlueprints_ResponsePubSubType::~GetBlueprints_ResponsePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool GetBlueprints_ResponsePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + GetBlueprints_Response* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool GetBlueprints_ResponsePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + GetBlueprints_Response* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function GetBlueprints_ResponsePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* GetBlueprints_ResponsePubSubType::createData() + { + return reinterpret_cast(new GetBlueprints_Response()); + } + + void GetBlueprints_ResponsePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool GetBlueprints_ResponsePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + GetBlueprints_Response* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + GetBlueprints_Response::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || GetBlueprints_Response::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace srv + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprintsPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprintsPubSubTypes.h new file mode 100644 index 00000000000..d609fa66c15 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprintsPubSubTypes.h @@ -0,0 +1,171 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file GetBlueprintsPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETBLUEPRINTS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETBLUEPRINTS_PUBSUBTYPES_H_ + +#include +#include + +#include "GetBlueprints.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated GetBlueprints is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace srv + { + /*! + * @brief This class represents the TopicDataType of the type GetBlueprints_Request defined by the user in the IDL file. + * @ingroup GETBLUEPRINTS + */ + class GetBlueprints_RequestPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef GetBlueprints_Request type; + + eProsima_user_DllExport GetBlueprints_RequestPubSubType(); + + eProsima_user_DllExport virtual ~GetBlueprints_RequestPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + /*! + * @brief This class represents the TopicDataType of the type GetBlueprints_Response defined by the user in the IDL file. + * @ingroup GETBLUEPRINTS + */ + class GetBlueprints_ResponsePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef GetBlueprints_Response type; + + eProsima_user_DllExport GetBlueprints_ResponsePubSubType(); + + eProsima_user_DllExport virtual ~GetBlueprints_ResponsePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETBLUEPRINTS_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMap.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMap.cxx new file mode 100644 index 00000000000..8b0e9aab91a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMap.cxx @@ -0,0 +1,479 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LoadMap.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "LoadMap.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + + + + + + +carla_msgs::srv::LoadMap_Request::LoadMap_Request() +{ + // m_mapname com.eprosima.idl.parser.typecode.StringTypeCode@3d3fcdb0 + m_mapname =""; + // m_force_reload com.eprosima.idl.parser.typecode.PrimitiveTypeCode@641147d0 + m_force_reload = false; + // m_reset_episode_settings com.eprosima.idl.parser.typecode.PrimitiveTypeCode@6e38921c + m_reset_episode_settings = true; + // m_map_layers com.eprosima.idl.parser.typecode.PrimitiveTypeCode@64d7f7e0 + m_map_layers = 65535; + +} + +carla_msgs::srv::LoadMap_Request::~LoadMap_Request() +{ + + + +} + +carla_msgs::srv::LoadMap_Request::LoadMap_Request( + const LoadMap_Request& x) +{ + m_mapname = x.m_mapname; + m_force_reload = x.m_force_reload; + m_reset_episode_settings = x.m_reset_episode_settings; + m_map_layers = x.m_map_layers; +} + +carla_msgs::srv::LoadMap_Request::LoadMap_Request( + LoadMap_Request&& x) +{ + m_mapname = std::move(x.m_mapname); + m_force_reload = x.m_force_reload; + m_reset_episode_settings = x.m_reset_episode_settings; + m_map_layers = x.m_map_layers; +} + +carla_msgs::srv::LoadMap_Request& carla_msgs::srv::LoadMap_Request::operator =( + const LoadMap_Request& x) +{ + + m_mapname = x.m_mapname; + m_force_reload = x.m_force_reload; + m_reset_episode_settings = x.m_reset_episode_settings; + m_map_layers = x.m_map_layers; + + return *this; +} + +carla_msgs::srv::LoadMap_Request& carla_msgs::srv::LoadMap_Request::operator =( + LoadMap_Request&& x) +{ + + m_mapname = std::move(x.m_mapname); + m_force_reload = x.m_force_reload; + m_reset_episode_settings = x.m_reset_episode_settings; + m_map_layers = x.m_map_layers; + + return *this; +} + +bool carla_msgs::srv::LoadMap_Request::operator ==( + const LoadMap_Request& x) const +{ + + return (m_mapname == x.m_mapname && m_force_reload == x.m_force_reload && m_reset_episode_settings == x.m_reset_episode_settings && m_map_layers == x.m_map_layers); +} + +bool carla_msgs::srv::LoadMap_Request::operator !=( + const LoadMap_Request& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::srv::LoadMap_Request::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::srv::LoadMap_Request::getCdrSerializedSize( + const carla_msgs::srv::LoadMap_Request& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.mapname().size() + 1; + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + + return current_alignment - initial_alignment; +} + +void carla_msgs::srv::LoadMap_Request::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_mapname; + scdr << m_force_reload; + scdr << m_reset_episode_settings; + scdr << m_map_layers; + +} + +void carla_msgs::srv::LoadMap_Request::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_mapname; + dcdr >> m_force_reload; + dcdr >> m_reset_episode_settings; + dcdr >> m_map_layers; +} + +/*! + * @brief This function copies the value in member mapname + * @param _mapname New value to be copied in member mapname + */ +void carla_msgs::srv::LoadMap_Request::mapname( + const std::string& _mapname) +{ + m_mapname = _mapname; +} + +/*! + * @brief This function moves the value in member mapname + * @param _mapname New value to be moved in member mapname + */ +void carla_msgs::srv::LoadMap_Request::mapname( + std::string&& _mapname) +{ + m_mapname = std::move(_mapname); +} + +/*! + * @brief This function returns a constant reference to member mapname + * @return Constant reference to member mapname + */ +const std::string& carla_msgs::srv::LoadMap_Request::mapname() const +{ + return m_mapname; +} + +/*! + * @brief This function returns a reference to member mapname + * @return Reference to member mapname + */ +std::string& carla_msgs::srv::LoadMap_Request::mapname() +{ + return m_mapname; +} +/*! + * @brief This function sets a value in member force_reload + * @param _force_reload New value for member force_reload + */ +void carla_msgs::srv::LoadMap_Request::force_reload( + bool _force_reload) +{ + m_force_reload = _force_reload; +} + +/*! + * @brief This function returns the value of member force_reload + * @return Value of member force_reload + */ +bool carla_msgs::srv::LoadMap_Request::force_reload() const +{ + return m_force_reload; +} + +/*! + * @brief This function returns a reference to member force_reload + * @return Reference to member force_reload + */ +bool& carla_msgs::srv::LoadMap_Request::force_reload() +{ + return m_force_reload; +} + +/*! + * @brief This function sets a value in member reset_episode_settings + * @param _reset_episode_settings New value for member reset_episode_settings + */ +void carla_msgs::srv::LoadMap_Request::reset_episode_settings( + bool _reset_episode_settings) +{ + m_reset_episode_settings = _reset_episode_settings; +} + +/*! + * @brief This function returns the value of member reset_episode_settings + * @return Value of member reset_episode_settings + */ +bool carla_msgs::srv::LoadMap_Request::reset_episode_settings() const +{ + return m_reset_episode_settings; +} + +/*! + * @brief This function returns a reference to member reset_episode_settings + * @return Reference to member reset_episode_settings + */ +bool& carla_msgs::srv::LoadMap_Request::reset_episode_settings() +{ + return m_reset_episode_settings; +} + +/*! + * @brief This function sets a value in member map_layers + * @param _map_layers New value for member map_layers + */ +void carla_msgs::srv::LoadMap_Request::map_layers( + uint16_t _map_layers) +{ + m_map_layers = _map_layers; +} + +/*! + * @brief This function returns the value of member map_layers + * @return Value of member map_layers + */ +uint16_t carla_msgs::srv::LoadMap_Request::map_layers() const +{ + return m_map_layers; +} + +/*! + * @brief This function returns a reference to member map_layers + * @return Reference to member map_layers + */ +uint16_t& carla_msgs::srv::LoadMap_Request::map_layers() +{ + return m_map_layers; +} + + +size_t carla_msgs::srv::LoadMap_Request::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::srv::LoadMap_Request::isKeyDefined() +{ + return false; +} + +void carla_msgs::srv::LoadMap_Request::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + +carla_msgs::srv::LoadMap_Response::LoadMap_Response() +{ + // m_success com.eprosima.idl.parser.typecode.PrimitiveTypeCode@ba8d91c + m_success = false; + +} + +carla_msgs::srv::LoadMap_Response::~LoadMap_Response() +{ +} + +carla_msgs::srv::LoadMap_Response::LoadMap_Response( + const LoadMap_Response& x) +{ + m_success = x.m_success; +} + +carla_msgs::srv::LoadMap_Response::LoadMap_Response( + LoadMap_Response&& x) +{ + m_success = x.m_success; +} + +carla_msgs::srv::LoadMap_Response& carla_msgs::srv::LoadMap_Response::operator =( + const LoadMap_Response& x) +{ + + m_success = x.m_success; + + return *this; +} + +carla_msgs::srv::LoadMap_Response& carla_msgs::srv::LoadMap_Response::operator =( + LoadMap_Response&& x) +{ + + m_success = x.m_success; + + return *this; +} + +bool carla_msgs::srv::LoadMap_Response::operator ==( + const LoadMap_Response& x) const +{ + + return (m_success == x.m_success); +} + +bool carla_msgs::srv::LoadMap_Response::operator !=( + const LoadMap_Response& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::srv::LoadMap_Response::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::srv::LoadMap_Response::getCdrSerializedSize( + const carla_msgs::srv::LoadMap_Response& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void carla_msgs::srv::LoadMap_Response::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_success; + +} + +void carla_msgs::srv::LoadMap_Response::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_success; +} + +/*! + * @brief This function sets a value in member success + * @param _success New value for member success + */ +void carla_msgs::srv::LoadMap_Response::success( + bool _success) +{ + m_success = _success; +} + +/*! + * @brief This function returns the value of member success + * @return Value of member success + */ +bool carla_msgs::srv::LoadMap_Response::success() const +{ + return m_success; +} + +/*! + * @brief This function returns a reference to member success + * @return Reference to member success + */ +bool& carla_msgs::srv::LoadMap_Response::success() +{ + return m_success; +} + + +size_t carla_msgs::srv::LoadMap_Response::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::srv::LoadMap_Response::isKeyDefined() +{ + return false; +} + +void carla_msgs::srv::LoadMap_Response::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMap.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMap.h new file mode 100644 index 00000000000..a990e38e04c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMap.h @@ -0,0 +1,430 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LoadMap.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_LOADMAP_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_LOADMAP_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(LoadMap_SOURCE) +#define LoadMap_DllAPI __declspec( dllexport ) +#else +#define LoadMap_DllAPI __declspec( dllimport ) +#endif // LoadMap_SOURCE +#else +#define LoadMap_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define LoadMap_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace srv { + namespace LoadMap_Request_Constants { + const uint16_t MAPLAYERFLAG_NONE = 0; + const uint16_t MAPLAYERFLAG_BUILDINGS = 1; + const uint16_t MAPLAYERFLAG_DECALS = 2; + const uint16_t MAPLAYERFLAG_FOLIAGE = 4; + const uint16_t MAPLAYERFLAG_GROUND = 8; + const uint16_t MAPLAYERFLAG_PARKEDVEHICLES = 16; + const uint16_t MAPLAYERFLAG_PARTICLES = 32; + const uint16_t MAPLAYERFLAG_PROPS = 64; + const uint16_t MAPLAYERFLAG_STREETLIGHTS = 128; + const uint16_t MAPLAYERFLAG_WALLS = 256; + const uint16_t MAPLAYERFLAG_ALL = 65535; + } // namespace LoadMap_Request_Constants + /*! + * @brief This class represents the structure LoadMap_Request defined by the user in the IDL file. + * @ingroup LOADMAP + */ + class LoadMap_Request + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport LoadMap_Request(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~LoadMap_Request(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::srv::LoadMap_Request that will be copied. + */ + eProsima_user_DllExport LoadMap_Request( + const LoadMap_Request& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::srv::LoadMap_Request that will be copied. + */ + eProsima_user_DllExport LoadMap_Request( + LoadMap_Request&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::srv::LoadMap_Request that will be copied. + */ + eProsima_user_DllExport LoadMap_Request& operator =( + const LoadMap_Request& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::srv::LoadMap_Request that will be copied. + */ + eProsima_user_DllExport LoadMap_Request& operator =( + LoadMap_Request&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::LoadMap_Request object to compare. + */ + eProsima_user_DllExport bool operator ==( + const LoadMap_Request& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::LoadMap_Request object to compare. + */ + eProsima_user_DllExport bool operator !=( + const LoadMap_Request& x) const; + + /*! + * @brief This function copies the value in member mapname + * @param _mapname New value to be copied in member mapname + */ + eProsima_user_DllExport void mapname( + const std::string& _mapname); + + /*! + * @brief This function moves the value in member mapname + * @param _mapname New value to be moved in member mapname + */ + eProsima_user_DllExport void mapname( + std::string&& _mapname); + + /*! + * @brief This function returns a constant reference to member mapname + * @return Constant reference to member mapname + */ + eProsima_user_DllExport const std::string& mapname() const; + + /*! + * @brief This function returns a reference to member mapname + * @return Reference to member mapname + */ + eProsima_user_DllExport std::string& mapname(); + /*! + * @brief This function sets a value in member force_reload + * @param _force_reload New value for member force_reload + */ + eProsima_user_DllExport void force_reload( + bool _force_reload); + + /*! + * @brief This function returns the value of member force_reload + * @return Value of member force_reload + */ + eProsima_user_DllExport bool force_reload() const; + + /*! + * @brief This function returns a reference to member force_reload + * @return Reference to member force_reload + */ + eProsima_user_DllExport bool& force_reload(); + + /*! + * @brief This function sets a value in member reset_episode_settings + * @param _reset_episode_settings New value for member reset_episode_settings + */ + eProsima_user_DllExport void reset_episode_settings( + bool _reset_episode_settings); + + /*! + * @brief This function returns the value of member reset_episode_settings + * @return Value of member reset_episode_settings + */ + eProsima_user_DllExport bool reset_episode_settings() const; + + /*! + * @brief This function returns a reference to member reset_episode_settings + * @return Reference to member reset_episode_settings + */ + eProsima_user_DllExport bool& reset_episode_settings(); + + /*! + * @brief This function sets a value in member map_layers + * @param _map_layers New value for member map_layers + */ + eProsima_user_DllExport void map_layers( + uint16_t _map_layers); + + /*! + * @brief This function returns the value of member map_layers + * @return Value of member map_layers + */ + eProsima_user_DllExport uint16_t map_layers() const; + + /*! + * @brief This function returns a reference to member map_layers + * @return Reference to member map_layers + */ + eProsima_user_DllExport uint16_t& map_layers(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::srv::LoadMap_Request& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std::string m_mapname; + bool m_force_reload; + bool m_reset_episode_settings; + uint16_t m_map_layers; + }; + /*! + * @brief This class represents the structure LoadMap_Response defined by the user in the IDL file. + * @ingroup LOADMAP + */ + class LoadMap_Response + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport LoadMap_Response(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~LoadMap_Response(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::srv::LoadMap_Response that will be copied. + */ + eProsima_user_DllExport LoadMap_Response( + const LoadMap_Response& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::srv::LoadMap_Response that will be copied. + */ + eProsima_user_DllExport LoadMap_Response( + LoadMap_Response&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::srv::LoadMap_Response that will be copied. + */ + eProsima_user_DllExport LoadMap_Response& operator =( + const LoadMap_Response& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::srv::LoadMap_Response that will be copied. + */ + eProsima_user_DllExport LoadMap_Response& operator =( + LoadMap_Response&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::LoadMap_Response object to compare. + */ + eProsima_user_DllExport bool operator ==( + const LoadMap_Response& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::LoadMap_Response object to compare. + */ + eProsima_user_DllExport bool operator !=( + const LoadMap_Response& x) const; + + /*! + * @brief This function sets a value in member success + * @param _success New value for member success + */ + eProsima_user_DllExport void success( + bool _success); + + /*! + * @brief This function returns the value of member success + * @return Value of member success + */ + eProsima_user_DllExport bool success() const; + + /*! + * @brief This function returns a reference to member success + * @return Reference to member success + */ + eProsima_user_DllExport bool& success(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::srv::LoadMap_Response& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + bool m_success; + }; + } // namespace srv +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_LOADMAP_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMapPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMapPubSubTypes.cxx new file mode 100644 index 00000000000..f1832f0b6fc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMapPubSubTypes.cxx @@ -0,0 +1,330 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LoadMapPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "LoadMapPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace srv { + namespace LoadMap_Request_Constants { + + + + + + + + + + + + + } //End of namespace LoadMap_Request_Constants + LoadMap_RequestPubSubType::LoadMap_RequestPubSubType() + { + setName("carla_msgs::srv::dds_::LoadMap_Request_"); + auto type_size = LoadMap_Request::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = LoadMap_Request::isKeyDefined(); + size_t keyLength = LoadMap_Request::getKeyMaxCdrSerializedSize() > 16 ? + LoadMap_Request::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + LoadMap_RequestPubSubType::~LoadMap_RequestPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool LoadMap_RequestPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + LoadMap_Request* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool LoadMap_RequestPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + LoadMap_Request* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function LoadMap_RequestPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* LoadMap_RequestPubSubType::createData() + { + return reinterpret_cast(new LoadMap_Request()); + } + + void LoadMap_RequestPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool LoadMap_RequestPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + LoadMap_Request* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + LoadMap_Request::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || LoadMap_Request::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + LoadMap_ResponsePubSubType::LoadMap_ResponsePubSubType() + { + setName("carla_msgs::srv::dds_::LoadMap_Response_"); + auto type_size = LoadMap_Response::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = LoadMap_Response::isKeyDefined(); + size_t keyLength = LoadMap_Response::getKeyMaxCdrSerializedSize() > 16 ? + LoadMap_Response::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + LoadMap_ResponsePubSubType::~LoadMap_ResponsePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool LoadMap_ResponsePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + LoadMap_Response* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool LoadMap_ResponsePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + LoadMap_Response* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function LoadMap_ResponsePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* LoadMap_ResponsePubSubType::createData() + { + return reinterpret_cast(new LoadMap_Response()); + } + + void LoadMap_ResponsePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool LoadMap_ResponsePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + LoadMap_Response* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + LoadMap_Response::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || LoadMap_Response::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace srv + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMapPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMapPubSubTypes.h new file mode 100644 index 00000000000..49c03382c12 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMapPubSubTypes.h @@ -0,0 +1,185 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LoadMapPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_LOADMAP_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_LOADMAP_PUBSUBTYPES_H_ + +#include +#include + +#include "LoadMap.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated LoadMap is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace srv + { + namespace LoadMap_Request_Constants + { + + + + + + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type LoadMap_Request defined by the user in the IDL file. + * @ingroup LOADMAP + */ + class LoadMap_RequestPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef LoadMap_Request type; + + eProsima_user_DllExport LoadMap_RequestPubSubType(); + + eProsima_user_DllExport virtual ~LoadMap_RequestPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + /*! + * @brief This class represents the TopicDataType of the type LoadMap_Response defined by the user in the IDL file. + * @ingroup LOADMAP + */ + class LoadMap_ResponsePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef LoadMap_Response type; + + eProsima_user_DllExport LoadMap_ResponsePubSubType(); + + eProsima_user_DllExport virtual ~LoadMap_ResponsePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) LoadMap_Response(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_LOADMAP_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettings.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettings.cxx new file mode 100644 index 00000000000..d799de62933 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettings.cxx @@ -0,0 +1,336 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SetEpisodeSettings.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "SetEpisodeSettings.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::srv::SetEpisodeSettings_Request::SetEpisodeSettings_Request() +{ + // m_episode_settings com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@79ca92b9 + + +} + +carla_msgs::srv::SetEpisodeSettings_Request::~SetEpisodeSettings_Request() +{ +} + +carla_msgs::srv::SetEpisodeSettings_Request::SetEpisodeSettings_Request( + const SetEpisodeSettings_Request& x) +{ + m_episode_settings = x.m_episode_settings; +} + +carla_msgs::srv::SetEpisodeSettings_Request::SetEpisodeSettings_Request( + SetEpisodeSettings_Request&& x) +{ + m_episode_settings = std::move(x.m_episode_settings); +} + +carla_msgs::srv::SetEpisodeSettings_Request& carla_msgs::srv::SetEpisodeSettings_Request::operator =( + const SetEpisodeSettings_Request& x) +{ + + m_episode_settings = x.m_episode_settings; + + return *this; +} + +carla_msgs::srv::SetEpisodeSettings_Request& carla_msgs::srv::SetEpisodeSettings_Request::operator =( + SetEpisodeSettings_Request&& x) +{ + + m_episode_settings = std::move(x.m_episode_settings); + + return *this; +} + +bool carla_msgs::srv::SetEpisodeSettings_Request::operator ==( + const SetEpisodeSettings_Request& x) const +{ + + return (m_episode_settings == x.m_episode_settings); +} + +bool carla_msgs::srv::SetEpisodeSettings_Request::operator !=( + const SetEpisodeSettings_Request& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::srv::SetEpisodeSettings_Request::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += carla_msgs::msg::CarlaEpisodeSettings::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::srv::SetEpisodeSettings_Request::getCdrSerializedSize( + const carla_msgs::srv::SetEpisodeSettings_Request& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += carla_msgs::msg::CarlaEpisodeSettings::getCdrSerializedSize(data.episode_settings(), current_alignment); + + return current_alignment - initial_alignment; +} + +void carla_msgs::srv::SetEpisodeSettings_Request::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_episode_settings; + +} + +void carla_msgs::srv::SetEpisodeSettings_Request::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_episode_settings; +} + +/*! + * @brief This function copies the value in member episode_settings + * @param _episode_settings New value to be copied in member episode_settings + */ +void carla_msgs::srv::SetEpisodeSettings_Request::episode_settings( + const carla_msgs::msg::CarlaEpisodeSettings& _episode_settings) +{ + m_episode_settings = _episode_settings; +} + +/*! + * @brief This function moves the value in member episode_settings + * @param _episode_settings New value to be moved in member episode_settings + */ +void carla_msgs::srv::SetEpisodeSettings_Request::episode_settings( + carla_msgs::msg::CarlaEpisodeSettings&& _episode_settings) +{ + m_episode_settings = std::move(_episode_settings); +} + +/*! + * @brief This function returns a constant reference to member episode_settings + * @return Constant reference to member episode_settings + */ +const carla_msgs::msg::CarlaEpisodeSettings& carla_msgs::srv::SetEpisodeSettings_Request::episode_settings() const +{ + return m_episode_settings; +} + +/*! + * @brief This function returns a reference to member episode_settings + * @return Reference to member episode_settings + */ +carla_msgs::msg::CarlaEpisodeSettings& carla_msgs::srv::SetEpisodeSettings_Request::episode_settings() +{ + return m_episode_settings; +} + +size_t carla_msgs::srv::SetEpisodeSettings_Request::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::srv::SetEpisodeSettings_Request::isKeyDefined() +{ + return false; +} + +void carla_msgs::srv::SetEpisodeSettings_Request::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + +carla_msgs::srv::SetEpisodeSettings_Response::SetEpisodeSettings_Response() +{ + // m_success com.eprosima.idl.parser.typecode.PrimitiveTypeCode@2aa3cd93 + m_success = false; + +} + +carla_msgs::srv::SetEpisodeSettings_Response::~SetEpisodeSettings_Response() +{ +} + +carla_msgs::srv::SetEpisodeSettings_Response::SetEpisodeSettings_Response( + const SetEpisodeSettings_Response& x) +{ + m_success = x.m_success; +} + +carla_msgs::srv::SetEpisodeSettings_Response::SetEpisodeSettings_Response( + SetEpisodeSettings_Response&& x) +{ + m_success = x.m_success; +} + +carla_msgs::srv::SetEpisodeSettings_Response& carla_msgs::srv::SetEpisodeSettings_Response::operator =( + const SetEpisodeSettings_Response& x) +{ + + m_success = x.m_success; + + return *this; +} + +carla_msgs::srv::SetEpisodeSettings_Response& carla_msgs::srv::SetEpisodeSettings_Response::operator =( + SetEpisodeSettings_Response&& x) +{ + + m_success = x.m_success; + + return *this; +} + +bool carla_msgs::srv::SetEpisodeSettings_Response::operator ==( + const SetEpisodeSettings_Response& x) const +{ + + return (m_success == x.m_success); +} + +bool carla_msgs::srv::SetEpisodeSettings_Response::operator !=( + const SetEpisodeSettings_Response& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::srv::SetEpisodeSettings_Response::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::srv::SetEpisodeSettings_Response::getCdrSerializedSize( + const carla_msgs::srv::SetEpisodeSettings_Response& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void carla_msgs::srv::SetEpisodeSettings_Response::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_success; + +} + +void carla_msgs::srv::SetEpisodeSettings_Response::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_success; +} + +/*! + * @brief This function sets a value in member success + * @param _success New value for member success + */ +void carla_msgs::srv::SetEpisodeSettings_Response::success( + bool _success) +{ + m_success = _success; +} + +/*! + * @brief This function returns the value of member success + * @return Value of member success + */ +bool carla_msgs::srv::SetEpisodeSettings_Response::success() const +{ + return m_success; +} + +/*! + * @brief This function returns a reference to member success + * @return Reference to member success + */ +bool& carla_msgs::srv::SetEpisodeSettings_Response::success() +{ + return m_success; +} + + +size_t carla_msgs::srv::SetEpisodeSettings_Response::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::srv::SetEpisodeSettings_Response::isKeyDefined() +{ + return false; +} + +void carla_msgs::srv::SetEpisodeSettings_Response::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettings.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettings.h new file mode 100644 index 00000000000..3663969b5ee --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettings.h @@ -0,0 +1,358 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SetEpisodeSettings.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SETEPISODESETTINGS_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SETEPISODESETTINGS_H_ + +#include "carla_msgs/msg/CarlaEpisodeSettings.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(SetEpisodeSettings_SOURCE) +#define SetEpisodeSettings_DllAPI __declspec( dllexport ) +#else +#define SetEpisodeSettings_DllAPI __declspec( dllimport ) +#endif // SetEpisodeSettings_SOURCE +#else +#define SetEpisodeSettings_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define SetEpisodeSettings_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace srv { + /*! + * @brief This class represents the structure SetEpisodeSettings_Request defined by the user in the IDL file. + * @ingroup SETEPISODESETTINGS + */ + class SetEpisodeSettings_Request + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport SetEpisodeSettings_Request(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~SetEpisodeSettings_Request(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::srv::SetEpisodeSettings_Request that will be copied. + */ + eProsima_user_DllExport SetEpisodeSettings_Request( + const SetEpisodeSettings_Request& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::srv::SetEpisodeSettings_Request that will be copied. + */ + eProsima_user_DllExport SetEpisodeSettings_Request( + SetEpisodeSettings_Request&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::srv::SetEpisodeSettings_Request that will be copied. + */ + eProsima_user_DllExport SetEpisodeSettings_Request& operator =( + const SetEpisodeSettings_Request& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::srv::SetEpisodeSettings_Request that will be copied. + */ + eProsima_user_DllExport SetEpisodeSettings_Request& operator =( + SetEpisodeSettings_Request&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::SetEpisodeSettings_Request object to compare. + */ + eProsima_user_DllExport bool operator ==( + const SetEpisodeSettings_Request& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::SetEpisodeSettings_Request object to compare. + */ + eProsima_user_DllExport bool operator !=( + const SetEpisodeSettings_Request& x) const; + + /*! + * @brief This function copies the value in member episode_settings + * @param _episode_settings New value to be copied in member episode_settings + */ + eProsima_user_DllExport void episode_settings( + const carla_msgs::msg::CarlaEpisodeSettings& _episode_settings); + + /*! + * @brief This function moves the value in member episode_settings + * @param _episode_settings New value to be moved in member episode_settings + */ + eProsima_user_DllExport void episode_settings( + carla_msgs::msg::CarlaEpisodeSettings&& _episode_settings); + + /*! + * @brief This function returns a constant reference to member episode_settings + * @return Constant reference to member episode_settings + */ + eProsima_user_DllExport const carla_msgs::msg::CarlaEpisodeSettings& episode_settings() const; + + /*! + * @brief This function returns a reference to member episode_settings + * @return Reference to member episode_settings + */ + eProsima_user_DllExport carla_msgs::msg::CarlaEpisodeSettings& episode_settings(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::srv::SetEpisodeSettings_Request& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + carla_msgs::msg::CarlaEpisodeSettings m_episode_settings; + }; + /*! + * @brief This class represents the structure SetEpisodeSettings_Response defined by the user in the IDL file. + * @ingroup SETEPISODESETTINGS + */ + class SetEpisodeSettings_Response + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport SetEpisodeSettings_Response(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~SetEpisodeSettings_Response(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::srv::SetEpisodeSettings_Response that will be copied. + */ + eProsima_user_DllExport SetEpisodeSettings_Response( + const SetEpisodeSettings_Response& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::srv::SetEpisodeSettings_Response that will be copied. + */ + eProsima_user_DllExport SetEpisodeSettings_Response( + SetEpisodeSettings_Response&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::srv::SetEpisodeSettings_Response that will be copied. + */ + eProsima_user_DllExport SetEpisodeSettings_Response& operator =( + const SetEpisodeSettings_Response& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::srv::SetEpisodeSettings_Response that will be copied. + */ + eProsima_user_DllExport SetEpisodeSettings_Response& operator =( + SetEpisodeSettings_Response&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::SetEpisodeSettings_Response object to compare. + */ + eProsima_user_DllExport bool operator ==( + const SetEpisodeSettings_Response& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::SetEpisodeSettings_Response object to compare. + */ + eProsima_user_DllExport bool operator !=( + const SetEpisodeSettings_Response& x) const; + + /*! + * @brief This function sets a value in member success + * @param _success New value for member success + */ + eProsima_user_DllExport void success( + bool _success); + + /*! + * @brief This function returns the value of member success + * @return Value of member success + */ + eProsima_user_DllExport bool success() const; + + /*! + * @brief This function returns a reference to member success + * @return Reference to member success + */ + eProsima_user_DllExport bool& success(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::srv::SetEpisodeSettings_Response& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + bool m_success; + }; + } // namespace srv +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SETEPISODESETTINGS_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettingsPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettingsPubSubTypes.cxx new file mode 100644 index 00000000000..7b146a803f2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettingsPubSubTypes.cxx @@ -0,0 +1,316 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SetEpisodeSettingsPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "SetEpisodeSettingsPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace srv { + SetEpisodeSettings_RequestPubSubType::SetEpisodeSettings_RequestPubSubType() + { + setName("carla_msgs::srv::dds_::SetEpisodeSettings_Request_"); + auto type_size = SetEpisodeSettings_Request::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = SetEpisodeSettings_Request::isKeyDefined(); + size_t keyLength = SetEpisodeSettings_Request::getKeyMaxCdrSerializedSize() > 16 ? + SetEpisodeSettings_Request::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + SetEpisodeSettings_RequestPubSubType::~SetEpisodeSettings_RequestPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool SetEpisodeSettings_RequestPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + SetEpisodeSettings_Request* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool SetEpisodeSettings_RequestPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + SetEpisodeSettings_Request* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function SetEpisodeSettings_RequestPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* SetEpisodeSettings_RequestPubSubType::createData() + { + return reinterpret_cast(new SetEpisodeSettings_Request()); + } + + void SetEpisodeSettings_RequestPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool SetEpisodeSettings_RequestPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + SetEpisodeSettings_Request* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + SetEpisodeSettings_Request::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || SetEpisodeSettings_Request::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + SetEpisodeSettings_ResponsePubSubType::SetEpisodeSettings_ResponsePubSubType() + { + setName("carla_msgs::srv::dds_::SetEpisodeSettings_Response_"); + auto type_size = SetEpisodeSettings_Response::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = SetEpisodeSettings_Response::isKeyDefined(); + size_t keyLength = SetEpisodeSettings_Response::getKeyMaxCdrSerializedSize() > 16 ? + SetEpisodeSettings_Response::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + SetEpisodeSettings_ResponsePubSubType::~SetEpisodeSettings_ResponsePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool SetEpisodeSettings_ResponsePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + SetEpisodeSettings_Response* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool SetEpisodeSettings_ResponsePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + SetEpisodeSettings_Response* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function SetEpisodeSettings_ResponsePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* SetEpisodeSettings_ResponsePubSubType::createData() + { + return reinterpret_cast(new SetEpisodeSettings_Response()); + } + + void SetEpisodeSettings_ResponsePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool SetEpisodeSettings_ResponsePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + SetEpisodeSettings_Response* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + SetEpisodeSettings_Response::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || SetEpisodeSettings_Response::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace srv + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettingsPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettingsPubSubTypes.h new file mode 100644 index 00000000000..0257b5be409 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettingsPubSubTypes.h @@ -0,0 +1,171 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SetEpisodeSettingsPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SETEPISODESETTINGS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SETEPISODESETTINGS_PUBSUBTYPES_H_ + +#include +#include + +#include "SetEpisodeSettings.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated SetEpisodeSettings is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace srv + { + /*! + * @brief This class represents the TopicDataType of the type SetEpisodeSettings_Request defined by the user in the IDL file. + * @ingroup SETEPISODESETTINGS + */ + class SetEpisodeSettings_RequestPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef SetEpisodeSettings_Request type; + + eProsima_user_DllExport SetEpisodeSettings_RequestPubSubType(); + + eProsima_user_DllExport virtual ~SetEpisodeSettings_RequestPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) SetEpisodeSettings_Request(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + /*! + * @brief This class represents the TopicDataType of the type SetEpisodeSettings_Response defined by the user in the IDL file. + * @ingroup SETEPISODESETTINGS + */ + class SetEpisodeSettings_ResponsePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef SetEpisodeSettings_Response type; + + eProsima_user_DllExport SetEpisodeSettings_ResponsePubSubType(); + + eProsima_user_DllExport virtual ~SetEpisodeSettings_ResponsePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) SetEpisodeSettings_Response(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SETEPISODESETTINGS_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObject.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObject.cxx new file mode 100644 index 00000000000..9edb18c717b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObject.cxx @@ -0,0 +1,522 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpawnObject.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "SpawnObject.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +carla_msgs::srv::SpawnObject_Request::SpawnObject_Request() +{ + // m_blueprint com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@1622f1b + + // m_transform com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@72a7c7e0 + + // m_attach_to com.eprosima.idl.parser.typecode.PrimitiveTypeCode@2e4b8173 + m_attach_to = 0; + // m_random_pose com.eprosima.idl.parser.typecode.PrimitiveTypeCode@70e8f8e + m_random_pose = false; + +} + +carla_msgs::srv::SpawnObject_Request::~SpawnObject_Request() +{ + + + +} + +carla_msgs::srv::SpawnObject_Request::SpawnObject_Request( + const SpawnObject_Request& x) +{ + m_blueprint = x.m_blueprint; + m_transform = x.m_transform; + m_attach_to = x.m_attach_to; + m_random_pose = x.m_random_pose; +} + +carla_msgs::srv::SpawnObject_Request::SpawnObject_Request( + SpawnObject_Request&& x) +{ + m_blueprint = std::move(x.m_blueprint); + m_transform = std::move(x.m_transform); + m_attach_to = x.m_attach_to; + m_random_pose = x.m_random_pose; +} + +carla_msgs::srv::SpawnObject_Request& carla_msgs::srv::SpawnObject_Request::operator =( + const SpawnObject_Request& x) +{ + + m_blueprint = x.m_blueprint; + m_transform = x.m_transform; + m_attach_to = x.m_attach_to; + m_random_pose = x.m_random_pose; + + return *this; +} + +carla_msgs::srv::SpawnObject_Request& carla_msgs::srv::SpawnObject_Request::operator =( + SpawnObject_Request&& x) +{ + + m_blueprint = std::move(x.m_blueprint); + m_transform = std::move(x.m_transform); + m_attach_to = x.m_attach_to; + m_random_pose = x.m_random_pose; + + return *this; +} + +bool carla_msgs::srv::SpawnObject_Request::operator ==( + const SpawnObject_Request& x) const +{ + + return (m_blueprint == x.m_blueprint && m_transform == x.m_transform && m_attach_to == x.m_attach_to && m_random_pose == x.m_random_pose); +} + +bool carla_msgs::srv::SpawnObject_Request::operator !=( + const SpawnObject_Request& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::srv::SpawnObject_Request::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += carla_msgs::msg::CarlaActorBlueprint::getMaxCdrSerializedSize(current_alignment); + current_alignment += geometry_msgs::msg::Pose::getMaxCdrSerializedSize(current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::srv::SpawnObject_Request::getCdrSerializedSize( + const carla_msgs::srv::SpawnObject_Request& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += carla_msgs::msg::CarlaActorBlueprint::getCdrSerializedSize(data.blueprint(), current_alignment); + current_alignment += geometry_msgs::msg::Pose::getCdrSerializedSize(data.transform(), current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void carla_msgs::srv::SpawnObject_Request::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_blueprint; + scdr << m_transform; + scdr << m_attach_to; + scdr << m_random_pose; + +} + +void carla_msgs::srv::SpawnObject_Request::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_blueprint; + dcdr >> m_transform; + dcdr >> m_attach_to; + dcdr >> m_random_pose; +} + +/*! + * @brief This function copies the value in member blueprint + * @param _blueprint New value to be copied in member blueprint + */ +void carla_msgs::srv::SpawnObject_Request::blueprint( + const carla_msgs::msg::CarlaActorBlueprint& _blueprint) +{ + m_blueprint = _blueprint; +} + +/*! + * @brief This function moves the value in member blueprint + * @param _blueprint New value to be moved in member blueprint + */ +void carla_msgs::srv::SpawnObject_Request::blueprint( + carla_msgs::msg::CarlaActorBlueprint&& _blueprint) +{ + m_blueprint = std::move(_blueprint); +} + +/*! + * @brief This function returns a constant reference to member blueprint + * @return Constant reference to member blueprint + */ +const carla_msgs::msg::CarlaActorBlueprint& carla_msgs::srv::SpawnObject_Request::blueprint() const +{ + return m_blueprint; +} + +/*! + * @brief This function returns a reference to member blueprint + * @return Reference to member blueprint + */ +carla_msgs::msg::CarlaActorBlueprint& carla_msgs::srv::SpawnObject_Request::blueprint() +{ + return m_blueprint; +} +/*! + * @brief This function copies the value in member transform + * @param _transform New value to be copied in member transform + */ +void carla_msgs::srv::SpawnObject_Request::transform( + const geometry_msgs::msg::Pose& _transform) +{ + m_transform = _transform; +} + +/*! + * @brief This function moves the value in member transform + * @param _transform New value to be moved in member transform + */ +void carla_msgs::srv::SpawnObject_Request::transform( + geometry_msgs::msg::Pose&& _transform) +{ + m_transform = std::move(_transform); +} + +/*! + * @brief This function returns a constant reference to member transform + * @return Constant reference to member transform + */ +const geometry_msgs::msg::Pose& carla_msgs::srv::SpawnObject_Request::transform() const +{ + return m_transform; +} + +/*! + * @brief This function returns a reference to member transform + * @return Reference to member transform + */ +geometry_msgs::msg::Pose& carla_msgs::srv::SpawnObject_Request::transform() +{ + return m_transform; +} +/*! + * @brief This function sets a value in member attach_to + * @param _attach_to New value for member attach_to + */ +void carla_msgs::srv::SpawnObject_Request::attach_to( + uint32_t _attach_to) +{ + m_attach_to = _attach_to; +} + +/*! + * @brief This function returns the value of member attach_to + * @return Value of member attach_to + */ +uint32_t carla_msgs::srv::SpawnObject_Request::attach_to() const +{ + return m_attach_to; +} + +/*! + * @brief This function returns a reference to member attach_to + * @return Reference to member attach_to + */ +uint32_t& carla_msgs::srv::SpawnObject_Request::attach_to() +{ + return m_attach_to; +} + +/*! + * @brief This function sets a value in member random_pose + * @param _random_pose New value for member random_pose + */ +void carla_msgs::srv::SpawnObject_Request::random_pose( + bool _random_pose) +{ + m_random_pose = _random_pose; +} + +/*! + * @brief This function returns the value of member random_pose + * @return Value of member random_pose + */ +bool carla_msgs::srv::SpawnObject_Request::random_pose() const +{ + return m_random_pose; +} + +/*! + * @brief This function returns a reference to member random_pose + * @return Reference to member random_pose + */ +bool& carla_msgs::srv::SpawnObject_Request::random_pose() +{ + return m_random_pose; +} + + +size_t carla_msgs::srv::SpawnObject_Request::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::srv::SpawnObject_Request::isKeyDefined() +{ + return false; +} + +void carla_msgs::srv::SpawnObject_Request::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + +carla_msgs::srv::SpawnObject_Response::SpawnObject_Response() +{ + // m_id com.eprosima.idl.parser.typecode.PrimitiveTypeCode@5e82df6a + m_id = 0; + // m_error_string com.eprosima.idl.parser.typecode.StringTypeCode@3f197a46 + m_error_string =""; + +} + +carla_msgs::srv::SpawnObject_Response::~SpawnObject_Response() +{ + +} + +carla_msgs::srv::SpawnObject_Response::SpawnObject_Response( + const SpawnObject_Response& x) +{ + m_id = x.m_id; + m_error_string = x.m_error_string; +} + +carla_msgs::srv::SpawnObject_Response::SpawnObject_Response( + SpawnObject_Response&& x) +{ + m_id = x.m_id; + m_error_string = std::move(x.m_error_string); +} + +carla_msgs::srv::SpawnObject_Response& carla_msgs::srv::SpawnObject_Response::operator =( + const SpawnObject_Response& x) +{ + + m_id = x.m_id; + m_error_string = x.m_error_string; + + return *this; +} + +carla_msgs::srv::SpawnObject_Response& carla_msgs::srv::SpawnObject_Response::operator =( + SpawnObject_Response&& x) +{ + + m_id = x.m_id; + m_error_string = std::move(x.m_error_string); + + return *this; +} + +bool carla_msgs::srv::SpawnObject_Response::operator ==( + const SpawnObject_Response& x) const +{ + + return (m_id == x.m_id && m_error_string == x.m_error_string); +} + +bool carla_msgs::srv::SpawnObject_Response::operator !=( + const SpawnObject_Response& x) const +{ + return !(*this == x); +} + +size_t carla_msgs::srv::SpawnObject_Response::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + + + return current_alignment - initial_alignment; +} + +size_t carla_msgs::srv::SpawnObject_Response::getCdrSerializedSize( + const carla_msgs::srv::SpawnObject_Response& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.error_string().size() + 1; + + + return current_alignment - initial_alignment; +} + +void carla_msgs::srv::SpawnObject_Response::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_id; + scdr << m_error_string; + +} + +void carla_msgs::srv::SpawnObject_Response::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_id; + dcdr >> m_error_string; +} + +/*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ +void carla_msgs::srv::SpawnObject_Response::id( + int32_t _id) +{ + m_id = _id; +} + +/*! + * @brief This function returns the value of member id + * @return Value of member id + */ +int32_t carla_msgs::srv::SpawnObject_Response::id() const +{ + return m_id; +} + +/*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ +int32_t& carla_msgs::srv::SpawnObject_Response::id() +{ + return m_id; +} + +/*! + * @brief This function copies the value in member error_string + * @param _error_string New value to be copied in member error_string + */ +void carla_msgs::srv::SpawnObject_Response::error_string( + const std::string& _error_string) +{ + m_error_string = _error_string; +} + +/*! + * @brief This function moves the value in member error_string + * @param _error_string New value to be moved in member error_string + */ +void carla_msgs::srv::SpawnObject_Response::error_string( + std::string&& _error_string) +{ + m_error_string = std::move(_error_string); +} + +/*! + * @brief This function returns a constant reference to member error_string + * @return Constant reference to member error_string + */ +const std::string& carla_msgs::srv::SpawnObject_Response::error_string() const +{ + return m_error_string; +} + +/*! + * @brief This function returns a reference to member error_string + * @return Reference to member error_string + */ +std::string& carla_msgs::srv::SpawnObject_Response::error_string() +{ + return m_error_string; +} + +size_t carla_msgs::srv::SpawnObject_Response::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool carla_msgs::srv::SpawnObject_Response::isKeyDefined() +{ + return false; +} + +void carla_msgs::srv::SpawnObject_Response::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObject.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObject.h new file mode 100644 index 00000000000..5d2a9d4d783 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObject.h @@ -0,0 +1,451 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpawnObject.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SPAWNOBJECT_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SPAWNOBJECT_H_ + +#include "carla_msgs/msg/CarlaActorBlueprint.h" +#include "geometry_msgs/msg/Pose.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(SpawnObject_SOURCE) +#define SpawnObject_DllAPI __declspec( dllexport ) +#else +#define SpawnObject_DllAPI __declspec( dllimport ) +#endif // SpawnObject_SOURCE +#else +#define SpawnObject_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define SpawnObject_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace carla_msgs { + namespace srv { + /*! + * @brief This class represents the structure SpawnObject_Request defined by the user in the IDL file. + * @ingroup SPAWNOBJECT + */ + class SpawnObject_Request + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport SpawnObject_Request(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~SpawnObject_Request(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::srv::SpawnObject_Request that will be copied. + */ + eProsima_user_DllExport SpawnObject_Request( + const SpawnObject_Request& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::srv::SpawnObject_Request that will be copied. + */ + eProsima_user_DllExport SpawnObject_Request( + SpawnObject_Request&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::srv::SpawnObject_Request that will be copied. + */ + eProsima_user_DllExport SpawnObject_Request& operator =( + const SpawnObject_Request& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::srv::SpawnObject_Request that will be copied. + */ + eProsima_user_DllExport SpawnObject_Request& operator =( + SpawnObject_Request&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::SpawnObject_Request object to compare. + */ + eProsima_user_DllExport bool operator ==( + const SpawnObject_Request& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::SpawnObject_Request object to compare. + */ + eProsima_user_DllExport bool operator !=( + const SpawnObject_Request& x) const; + + /*! + * @brief This function copies the value in member blueprint + * @param _blueprint New value to be copied in member blueprint + */ + eProsima_user_DllExport void blueprint( + const carla_msgs::msg::CarlaActorBlueprint& _blueprint); + + /*! + * @brief This function moves the value in member blueprint + * @param _blueprint New value to be moved in member blueprint + */ + eProsima_user_DllExport void blueprint( + carla_msgs::msg::CarlaActorBlueprint&& _blueprint); + + /*! + * @brief This function returns a constant reference to member blueprint + * @return Constant reference to member blueprint + */ + eProsima_user_DllExport const carla_msgs::msg::CarlaActorBlueprint& blueprint() const; + + /*! + * @brief This function returns a reference to member blueprint + * @return Reference to member blueprint + */ + eProsima_user_DllExport carla_msgs::msg::CarlaActorBlueprint& blueprint(); + /*! + * @brief This function copies the value in member transform + * @param _transform New value to be copied in member transform + */ + eProsima_user_DllExport void transform( + const geometry_msgs::msg::Pose& _transform); + + /*! + * @brief This function moves the value in member transform + * @param _transform New value to be moved in member transform + */ + eProsima_user_DllExport void transform( + geometry_msgs::msg::Pose&& _transform); + + /*! + * @brief This function returns a constant reference to member transform + * @return Constant reference to member transform + */ + eProsima_user_DllExport const geometry_msgs::msg::Pose& transform() const; + + /*! + * @brief This function returns a reference to member transform + * @return Reference to member transform + */ + eProsima_user_DllExport geometry_msgs::msg::Pose& transform(); + /*! + * @brief This function sets a value in member attach_to + * @param _attach_to New value for member attach_to + */ + eProsima_user_DllExport void attach_to( + uint32_t _attach_to); + + /*! + * @brief This function returns the value of member attach_to + * @return Value of member attach_to + */ + eProsima_user_DllExport uint32_t attach_to() const; + + /*! + * @brief This function returns a reference to member attach_to + * @return Reference to member attach_to + */ + eProsima_user_DllExport uint32_t& attach_to(); + + /*! + * @brief This function sets a value in member random_pose + * @param _random_pose New value for member random_pose + */ + eProsima_user_DllExport void random_pose( + bool _random_pose); + + /*! + * @brief This function returns the value of member random_pose + * @return Value of member random_pose + */ + eProsima_user_DllExport bool random_pose() const; + + /*! + * @brief This function returns a reference to member random_pose + * @return Reference to member random_pose + */ + eProsima_user_DllExport bool& random_pose(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::srv::SpawnObject_Request& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + carla_msgs::msg::CarlaActorBlueprint m_blueprint; + geometry_msgs::msg::Pose m_transform; + uint32_t m_attach_to; + bool m_random_pose; + }; + /*! + * @brief This class represents the structure SpawnObject_Response defined by the user in the IDL file. + * @ingroup SPAWNOBJECT + */ + class SpawnObject_Response + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport SpawnObject_Response(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~SpawnObject_Response(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::srv::SpawnObject_Response that will be copied. + */ + eProsima_user_DllExport SpawnObject_Response( + const SpawnObject_Response& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::srv::SpawnObject_Response that will be copied. + */ + eProsima_user_DllExport SpawnObject_Response( + SpawnObject_Response&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::srv::SpawnObject_Response that will be copied. + */ + eProsima_user_DllExport SpawnObject_Response& operator =( + const SpawnObject_Response& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::srv::SpawnObject_Response that will be copied. + */ + eProsima_user_DllExport SpawnObject_Response& operator =( + SpawnObject_Response&& x); + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::SpawnObject_Response object to compare. + */ + eProsima_user_DllExport bool operator ==( + const SpawnObject_Response& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::srv::SpawnObject_Response object to compare. + */ + eProsima_user_DllExport bool operator !=( + const SpawnObject_Response& x) const; + + /*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ + eProsima_user_DllExport void id( + int32_t _id); + + /*! + * @brief This function returns the value of member id + * @return Value of member id + */ + eProsima_user_DllExport int32_t id() const; + + /*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ + eProsima_user_DllExport int32_t& id(); + + /*! + * @brief This function copies the value in member error_string + * @param _error_string New value to be copied in member error_string + */ + eProsima_user_DllExport void error_string( + const std::string& _error_string); + + /*! + * @brief This function moves the value in member error_string + * @param _error_string New value to be moved in member error_string + */ + eProsima_user_DllExport void error_string( + std::string&& _error_string); + + /*! + * @brief This function returns a constant reference to member error_string + * @return Constant reference to member error_string + */ + eProsima_user_DllExport const std::string& error_string() const; + + /*! + * @brief This function returns a reference to member error_string + * @return Reference to member error_string + */ + eProsima_user_DllExport std::string& error_string(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const carla_msgs::srv::SpawnObject_Response& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + int32_t m_id; + std::string m_error_string; + }; + } // namespace srv +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SPAWNOBJECT_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObjectPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObjectPubSubTypes.cxx new file mode 100644 index 00000000000..4ead5374baf --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObjectPubSubTypes.cxx @@ -0,0 +1,316 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpawnObjectPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "SpawnObjectPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace carla_msgs { + namespace srv { + SpawnObject_RequestPubSubType::SpawnObject_RequestPubSubType() + { + setName("carla_msgs::srv::dds_::SpawnObject_Request_"); + auto type_size = SpawnObject_Request::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = SpawnObject_Request::isKeyDefined(); + size_t keyLength = SpawnObject_Request::getKeyMaxCdrSerializedSize() > 16 ? + SpawnObject_Request::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + SpawnObject_RequestPubSubType::~SpawnObject_RequestPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool SpawnObject_RequestPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + SpawnObject_Request* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool SpawnObject_RequestPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + SpawnObject_Request* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function SpawnObject_RequestPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* SpawnObject_RequestPubSubType::createData() + { + return reinterpret_cast(new SpawnObject_Request()); + } + + void SpawnObject_RequestPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool SpawnObject_RequestPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + SpawnObject_Request* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + SpawnObject_Request::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || SpawnObject_Request::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + SpawnObject_ResponsePubSubType::SpawnObject_ResponsePubSubType() + { + setName("carla_msgs::srv::dds_::SpawnObject_Response_"); + auto type_size = SpawnObject_Response::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = SpawnObject_Response::isKeyDefined(); + size_t keyLength = SpawnObject_Response::getKeyMaxCdrSerializedSize() > 16 ? + SpawnObject_Response::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + SpawnObject_ResponsePubSubType::~SpawnObject_ResponsePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool SpawnObject_ResponsePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + SpawnObject_Response* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool SpawnObject_ResponsePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + SpawnObject_Response* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function SpawnObject_ResponsePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* SpawnObject_ResponsePubSubType::createData() + { + return reinterpret_cast(new SpawnObject_Response()); + } + + void SpawnObject_ResponsePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool SpawnObject_ResponsePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + SpawnObject_Response* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + SpawnObject_Response::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || SpawnObject_Response::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace srv + +} //End of namespace carla_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObjectPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObjectPubSubTypes.h new file mode 100644 index 00000000000..a0cd80095ab --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObjectPubSubTypes.h @@ -0,0 +1,171 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpawnObjectPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SPAWNOBJECT_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SPAWNOBJECT_PUBSUBTYPES_H_ + +#include +#include + +#include "SpawnObject.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated SpawnObject is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs +{ + namespace srv + { + /*! + * @brief This class represents the TopicDataType of the type SpawnObject_Request defined by the user in the IDL file. + * @ingroup SPAWNOBJECT + */ + class SpawnObject_RequestPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef SpawnObject_Request type; + + eProsima_user_DllExport SpawnObject_RequestPubSubType(); + + eProsima_user_DllExport virtual ~SpawnObject_RequestPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + /*! + * @brief This class represents the TopicDataType of the type SpawnObject_Response defined by the user in the IDL file. + * @ingroup SPAWNOBJECT + */ + class SpawnObject_ResponsePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef SpawnObject_Response type; + + eProsima_user_DllExport SpawnObject_ResponsePubSubType(); + + eProsima_user_DllExport virtual ~SpawnObject_ResponsePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SPAWNOBJECT_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/Object.cxx b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/Object.cxx new file mode 100644 index 00000000000..3c4ed7cb410 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/Object.cxx @@ -0,0 +1,703 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Object.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Object.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + + + + + + + + + +derived_object_msgs::msg::Object::Object() +{ + // m_header com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@3cc1435c + + // m_id com.eprosima.idl.parser.typecode.PrimitiveTypeCode@6bf0219d + m_id = 0; + // m_detection_level com.eprosima.idl.parser.typecode.PrimitiveTypeCode@dd0c991 + m_detection_level = 0; + // m_object_classified com.eprosima.idl.parser.typecode.PrimitiveTypeCode@5f16132a + m_object_classified = false; + // m_pose com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@69fb6037 + + // m_twist com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@36d585c + + // m_accel com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@87a85e1 + + // m_polygon com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@671a5887 + + // m_shape com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@5552768b + + // m_classification com.eprosima.idl.parser.typecode.PrimitiveTypeCode@55f616cf + m_classification = 0; + // m_classification_certainty com.eprosima.idl.parser.typecode.PrimitiveTypeCode@1356d4d4 + m_classification_certainty = 0; + // m_classification_age com.eprosima.idl.parser.typecode.PrimitiveTypeCode@c03cf28 + m_classification_age = 0; + +} + +derived_object_msgs::msg::Object::~Object() +{ + + + + + + + + + + + +} + +derived_object_msgs::msg::Object::Object( + const Object& x) +{ + m_header = x.m_header; + m_id = x.m_id; + m_detection_level = x.m_detection_level; + m_object_classified = x.m_object_classified; + m_pose = x.m_pose; + m_twist = x.m_twist; + m_accel = x.m_accel; + m_polygon = x.m_polygon; + m_shape = x.m_shape; + m_classification = x.m_classification; + m_classification_certainty = x.m_classification_certainty; + m_classification_age = x.m_classification_age; +} + +derived_object_msgs::msg::Object::Object( + Object&& x) +{ + m_header = std::move(x.m_header); + m_id = x.m_id; + m_detection_level = x.m_detection_level; + m_object_classified = x.m_object_classified; + m_pose = std::move(x.m_pose); + m_twist = std::move(x.m_twist); + m_accel = std::move(x.m_accel); + m_polygon = std::move(x.m_polygon); + m_shape = std::move(x.m_shape); + m_classification = x.m_classification; + m_classification_certainty = x.m_classification_certainty; + m_classification_age = x.m_classification_age; +} + +derived_object_msgs::msg::Object& derived_object_msgs::msg::Object::operator =( + const Object& x) +{ + + m_header = x.m_header; + m_id = x.m_id; + m_detection_level = x.m_detection_level; + m_object_classified = x.m_object_classified; + m_pose = x.m_pose; + m_twist = x.m_twist; + m_accel = x.m_accel; + m_polygon = x.m_polygon; + m_shape = x.m_shape; + m_classification = x.m_classification; + m_classification_certainty = x.m_classification_certainty; + m_classification_age = x.m_classification_age; + + return *this; +} + +derived_object_msgs::msg::Object& derived_object_msgs::msg::Object::operator =( + Object&& x) +{ + + m_header = std::move(x.m_header); + m_id = x.m_id; + m_detection_level = x.m_detection_level; + m_object_classified = x.m_object_classified; + m_pose = std::move(x.m_pose); + m_twist = std::move(x.m_twist); + m_accel = std::move(x.m_accel); + m_polygon = std::move(x.m_polygon); + m_shape = std::move(x.m_shape); + m_classification = x.m_classification; + m_classification_certainty = x.m_classification_certainty; + m_classification_age = x.m_classification_age; + + return *this; +} + +bool derived_object_msgs::msg::Object::operator ==( + const Object& x) const +{ + + return (m_header == x.m_header && m_id == x.m_id && m_detection_level == x.m_detection_level && m_object_classified == x.m_object_classified && m_pose == x.m_pose && m_twist == x.m_twist && m_accel == x.m_accel && m_polygon == x.m_polygon && m_shape == x.m_shape && m_classification == x.m_classification && m_classification_certainty == x.m_classification_certainty && m_classification_age == x.m_classification_age); +} + +bool derived_object_msgs::msg::Object::operator !=( + const Object& x) const +{ + return !(*this == x); +} + +size_t derived_object_msgs::msg::Object::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getMaxCdrSerializedSize(current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += geometry_msgs::msg::Pose::getMaxCdrSerializedSize(current_alignment); + current_alignment += geometry_msgs::msg::Twist::getMaxCdrSerializedSize(current_alignment); + current_alignment += geometry_msgs::msg::Accel::getMaxCdrSerializedSize(current_alignment); + current_alignment += geometry_msgs::msg::Polygon::getMaxCdrSerializedSize(current_alignment); + current_alignment += shape_msgs::msg::SolidPrimitive::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + + return current_alignment - initial_alignment; +} + +size_t derived_object_msgs::msg::Object::getCdrSerializedSize( + const derived_object_msgs::msg::Object& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getCdrSerializedSize(data.header(), current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += geometry_msgs::msg::Pose::getCdrSerializedSize(data.pose(), current_alignment); + current_alignment += geometry_msgs::msg::Twist::getCdrSerializedSize(data.twist(), current_alignment); + current_alignment += geometry_msgs::msg::Accel::getCdrSerializedSize(data.accel(), current_alignment); + current_alignment += geometry_msgs::msg::Polygon::getCdrSerializedSize(data.polygon(), current_alignment); + current_alignment += shape_msgs::msg::SolidPrimitive::getCdrSerializedSize(data.shape(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + + return current_alignment - initial_alignment; +} + +void derived_object_msgs::msg::Object::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_header; + scdr << m_id; + scdr << m_detection_level; + scdr << m_object_classified; + scdr << m_pose; + scdr << m_twist; + scdr << m_accel; + scdr << m_polygon; + scdr << m_shape; + scdr << m_classification; + scdr << m_classification_certainty; + scdr << m_classification_age; + +} + +void derived_object_msgs::msg::Object::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_header; + dcdr >> m_id; + dcdr >> m_detection_level; + dcdr >> m_object_classified; + dcdr >> m_pose; + dcdr >> m_twist; + dcdr >> m_accel; + dcdr >> m_polygon; + dcdr >> m_shape; + dcdr >> m_classification; + dcdr >> m_classification_certainty; + dcdr >> m_classification_age; +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void derived_object_msgs::msg::Object::header( + const std_msgs::msg::Header& _header) +{ + m_header = _header; +} + +/*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ +void derived_object_msgs::msg::Object::header( + std_msgs::msg::Header&& _header) +{ + m_header = std::move(_header); +} + +/*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ +const std_msgs::msg::Header& derived_object_msgs::msg::Object::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& derived_object_msgs::msg::Object::header() +{ + return m_header; +} +/*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ +void derived_object_msgs::msg::Object::id( + uint32_t _id) +{ + m_id = _id; +} + +/*! + * @brief This function returns the value of member id + * @return Value of member id + */ +uint32_t derived_object_msgs::msg::Object::id() const +{ + return m_id; +} + +/*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ +uint32_t& derived_object_msgs::msg::Object::id() +{ + return m_id; +} + +/*! + * @brief This function sets a value in member detection_level + * @param _detection_level New value for member detection_level + */ +void derived_object_msgs::msg::Object::detection_level( + uint8_t _detection_level) +{ + m_detection_level = _detection_level; +} + +/*! + * @brief This function returns the value of member detection_level + * @return Value of member detection_level + */ +uint8_t derived_object_msgs::msg::Object::detection_level() const +{ + return m_detection_level; +} + +/*! + * @brief This function returns a reference to member detection_level + * @return Reference to member detection_level + */ +uint8_t& derived_object_msgs::msg::Object::detection_level() +{ + return m_detection_level; +} + +/*! + * @brief This function sets a value in member object_classified + * @param _object_classified New value for member object_classified + */ +void derived_object_msgs::msg::Object::object_classified( + bool _object_classified) +{ + m_object_classified = _object_classified; +} + +/*! + * @brief This function returns the value of member object_classified + * @return Value of member object_classified + */ +bool derived_object_msgs::msg::Object::object_classified() const +{ + return m_object_classified; +} + +/*! + * @brief This function returns a reference to member object_classified + * @return Reference to member object_classified + */ +bool& derived_object_msgs::msg::Object::object_classified() +{ + return m_object_classified; +} + +/*! + * @brief This function copies the value in member pose + * @param _pose New value to be copied in member pose + */ +void derived_object_msgs::msg::Object::pose( + const geometry_msgs::msg::Pose& _pose) +{ + m_pose = _pose; +} + +/*! + * @brief This function moves the value in member pose + * @param _pose New value to be moved in member pose + */ +void derived_object_msgs::msg::Object::pose( + geometry_msgs::msg::Pose&& _pose) +{ + m_pose = std::move(_pose); +} + +/*! + * @brief This function returns a constant reference to member pose + * @return Constant reference to member pose + */ +const geometry_msgs::msg::Pose& derived_object_msgs::msg::Object::pose() const +{ + return m_pose; +} + +/*! + * @brief This function returns a reference to member pose + * @return Reference to member pose + */ +geometry_msgs::msg::Pose& derived_object_msgs::msg::Object::pose() +{ + return m_pose; +} +/*! + * @brief This function copies the value in member twist + * @param _twist New value to be copied in member twist + */ +void derived_object_msgs::msg::Object::twist( + const geometry_msgs::msg::Twist& _twist) +{ + m_twist = _twist; +} + +/*! + * @brief This function moves the value in member twist + * @param _twist New value to be moved in member twist + */ +void derived_object_msgs::msg::Object::twist( + geometry_msgs::msg::Twist&& _twist) +{ + m_twist = std::move(_twist); +} + +/*! + * @brief This function returns a constant reference to member twist + * @return Constant reference to member twist + */ +const geometry_msgs::msg::Twist& derived_object_msgs::msg::Object::twist() const +{ + return m_twist; +} + +/*! + * @brief This function returns a reference to member twist + * @return Reference to member twist + */ +geometry_msgs::msg::Twist& derived_object_msgs::msg::Object::twist() +{ + return m_twist; +} +/*! + * @brief This function copies the value in member accel + * @param _accel New value to be copied in member accel + */ +void derived_object_msgs::msg::Object::accel( + const geometry_msgs::msg::Accel& _accel) +{ + m_accel = _accel; +} + +/*! + * @brief This function moves the value in member accel + * @param _accel New value to be moved in member accel + */ +void derived_object_msgs::msg::Object::accel( + geometry_msgs::msg::Accel&& _accel) +{ + m_accel = std::move(_accel); +} + +/*! + * @brief This function returns a constant reference to member accel + * @return Constant reference to member accel + */ +const geometry_msgs::msg::Accel& derived_object_msgs::msg::Object::accel() const +{ + return m_accel; +} + +/*! + * @brief This function returns a reference to member accel + * @return Reference to member accel + */ +geometry_msgs::msg::Accel& derived_object_msgs::msg::Object::accel() +{ + return m_accel; +} +/*! + * @brief This function copies the value in member polygon + * @param _polygon New value to be copied in member polygon + */ +void derived_object_msgs::msg::Object::polygon( + const geometry_msgs::msg::Polygon& _polygon) +{ + m_polygon = _polygon; +} + +/*! + * @brief This function moves the value in member polygon + * @param _polygon New value to be moved in member polygon + */ +void derived_object_msgs::msg::Object::polygon( + geometry_msgs::msg::Polygon&& _polygon) +{ + m_polygon = std::move(_polygon); +} + +/*! + * @brief This function returns a constant reference to member polygon + * @return Constant reference to member polygon + */ +const geometry_msgs::msg::Polygon& derived_object_msgs::msg::Object::polygon() const +{ + return m_polygon; +} + +/*! + * @brief This function returns a reference to member polygon + * @return Reference to member polygon + */ +geometry_msgs::msg::Polygon& derived_object_msgs::msg::Object::polygon() +{ + return m_polygon; +} +/*! + * @brief This function copies the value in member shape + * @param _shape New value to be copied in member shape + */ +void derived_object_msgs::msg::Object::shape( + const shape_msgs::msg::SolidPrimitive& _shape) +{ + m_shape = _shape; +} + +/*! + * @brief This function moves the value in member shape + * @param _shape New value to be moved in member shape + */ +void derived_object_msgs::msg::Object::shape( + shape_msgs::msg::SolidPrimitive&& _shape) +{ + m_shape = std::move(_shape); +} + +/*! + * @brief This function returns a constant reference to member shape + * @return Constant reference to member shape + */ +const shape_msgs::msg::SolidPrimitive& derived_object_msgs::msg::Object::shape() const +{ + return m_shape; +} + +/*! + * @brief This function returns a reference to member shape + * @return Reference to member shape + */ +shape_msgs::msg::SolidPrimitive& derived_object_msgs::msg::Object::shape() +{ + return m_shape; +} +/*! + * @brief This function sets a value in member classification + * @param _classification New value for member classification + */ +void derived_object_msgs::msg::Object::classification( + uint8_t _classification) +{ + m_classification = _classification; +} + +/*! + * @brief This function returns the value of member classification + * @return Value of member classification + */ +uint8_t derived_object_msgs::msg::Object::classification() const +{ + return m_classification; +} + +/*! + * @brief This function returns a reference to member classification + * @return Reference to member classification + */ +uint8_t& derived_object_msgs::msg::Object::classification() +{ + return m_classification; +} + +/*! + * @brief This function sets a value in member classification_certainty + * @param _classification_certainty New value for member classification_certainty + */ +void derived_object_msgs::msg::Object::classification_certainty( + uint8_t _classification_certainty) +{ + m_classification_certainty = _classification_certainty; +} + +/*! + * @brief This function returns the value of member classification_certainty + * @return Value of member classification_certainty + */ +uint8_t derived_object_msgs::msg::Object::classification_certainty() const +{ + return m_classification_certainty; +} + +/*! + * @brief This function returns a reference to member classification_certainty + * @return Reference to member classification_certainty + */ +uint8_t& derived_object_msgs::msg::Object::classification_certainty() +{ + return m_classification_certainty; +} + +/*! + * @brief This function sets a value in member classification_age + * @param _classification_age New value for member classification_age + */ +void derived_object_msgs::msg::Object::classification_age( + uint32_t _classification_age) +{ + m_classification_age = _classification_age; +} + +/*! + * @brief This function returns the value of member classification_age + * @return Value of member classification_age + */ +uint32_t derived_object_msgs::msg::Object::classification_age() const +{ + return m_classification_age; +} + +/*! + * @brief This function returns a reference to member classification_age + * @return Reference to member classification_age + */ +uint32_t& derived_object_msgs::msg::Object::classification_age() +{ + return m_classification_age; +} + + +size_t derived_object_msgs::msg::Object::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool derived_object_msgs::msg::Object::isKeyDefined() +{ + return false; +} + +void derived_object_msgs::msg::Object::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/Object.h b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/Object.h new file mode 100644 index 00000000000..5b24ea2ba73 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/Object.h @@ -0,0 +1,450 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Object.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECT_H_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECT_H_ + +#include "geometry_msgs/msg/Accel.h" +#include "geometry_msgs/msg/Polygon.h" +#include "geometry_msgs/msg/Pose.h" +#include "geometry_msgs/msg/Twist.h" +#include "shape_msgs/msg/SolidPrimitive.h" +#include "std_msgs/msg/Header.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(Object_SOURCE) +#define Object_DllAPI __declspec(dllexport) +#else +#define Object_DllAPI __declspec(dllimport) +#endif // Object_SOURCE +#else +#define Object_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define Object_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace derived_object_msgs { +namespace msg { +namespace Object_Constants { +const uint8_t OBJECT_DETECTED = 0; +const uint8_t OBJECT_TRACKED = 1; +const uint8_t CLASSIFICATION_UNKNOWN = 0; +const uint8_t CLASSIFICATION_UNKNOWN_SMALL = 1; +const uint8_t CLASSIFICATION_UNKNOWN_MEDIUM = 2; +const uint8_t CLASSIFICATION_UNKNOWN_BIG = 3; +const uint8_t CLASSIFICATION_PEDESTRIAN = 4; +const uint8_t CLASSIFICATION_BIKE = 5; +const uint8_t CLASSIFICATION_CAR = 6; +const uint8_t CLASSIFICATION_TRUCK = 7; +const uint8_t CLASSIFICATION_MOTORCYCLE = 8; +const uint8_t CLASSIFICATION_OTHER_VEHICLE = 9; +const uint8_t CLASSIFICATION_BARRIER = 10; +const uint8_t CLASSIFICATION_SIGN = 11; +} // namespace Object_Constants +/*! + * @brief This class represents the structure Object defined by the user in the IDL file. + * @ingroup OBJECT + */ +class Object { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Object(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Object(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object derived_object_msgs::msg::Object that will be copied. + */ + eProsima_user_DllExport Object(const Object& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object derived_object_msgs::msg::Object that will be copied. + */ + eProsima_user_DllExport Object(Object&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object derived_object_msgs::msg::Object that will be copied. + */ + eProsima_user_DllExport Object& operator=(const Object& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object derived_object_msgs::msg::Object that will be copied. + */ + eProsima_user_DllExport Object& operator=(Object&& x); + + /*! + * @brief Comparison operator. + * @param x derived_object_msgs::msg::Object object to compare. + */ + eProsima_user_DllExport bool operator==(const Object& x) const; + + /*! + * @brief Comparison operator. + * @param x derived_object_msgs::msg::Object object to compare. + */ + eProsima_user_DllExport bool operator!=(const Object& x) const; + + /*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ + eProsima_user_DllExport void header(const std_msgs::msg::Header& _header); + + /*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ + eProsima_user_DllExport void header(std_msgs::msg::Header&& _header); + + /*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ + eProsima_user_DllExport const std_msgs::msg::Header& header() const; + + /*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ + eProsima_user_DllExport std_msgs::msg::Header& header(); + /*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ + eProsima_user_DllExport void id(uint32_t _id); + + /*! + * @brief This function returns the value of member id + * @return Value of member id + */ + eProsima_user_DllExport uint32_t id() const; + + /*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ + eProsima_user_DllExport uint32_t& id(); + + /*! + * @brief This function sets a value in member detection_level + * @param _detection_level New value for member detection_level + */ + eProsima_user_DllExport void detection_level(uint8_t _detection_level); + + /*! + * @brief This function returns the value of member detection_level + * @return Value of member detection_level + */ + eProsima_user_DllExport uint8_t detection_level() const; + + /*! + * @brief This function returns a reference to member detection_level + * @return Reference to member detection_level + */ + eProsima_user_DllExport uint8_t& detection_level(); + + /*! + * @brief This function sets a value in member object_classified + * @param _object_classified New value for member object_classified + */ + eProsima_user_DllExport void object_classified(bool _object_classified); + + /*! + * @brief This function returns the value of member object_classified + * @return Value of member object_classified + */ + eProsima_user_DllExport bool object_classified() const; + + /*! + * @brief This function returns a reference to member object_classified + * @return Reference to member object_classified + */ + eProsima_user_DllExport bool& object_classified(); + + /*! + * @brief This function copies the value in member pose + * @param _pose New value to be copied in member pose + */ + eProsima_user_DllExport void pose(const geometry_msgs::msg::Pose& _pose); + + /*! + * @brief This function moves the value in member pose + * @param _pose New value to be moved in member pose + */ + eProsima_user_DllExport void pose(geometry_msgs::msg::Pose&& _pose); + + /*! + * @brief This function returns a constant reference to member pose + * @return Constant reference to member pose + */ + eProsima_user_DllExport const geometry_msgs::msg::Pose& pose() const; + + /*! + * @brief This function returns a reference to member pose + * @return Reference to member pose + */ + eProsima_user_DllExport geometry_msgs::msg::Pose& pose(); + /*! + * @brief This function copies the value in member twist + * @param _twist New value to be copied in member twist + */ + eProsima_user_DllExport void twist(const geometry_msgs::msg::Twist& _twist); + + /*! + * @brief This function moves the value in member twist + * @param _twist New value to be moved in member twist + */ + eProsima_user_DllExport void twist(geometry_msgs::msg::Twist&& _twist); + + /*! + * @brief This function returns a constant reference to member twist + * @return Constant reference to member twist + */ + eProsima_user_DllExport const geometry_msgs::msg::Twist& twist() const; + + /*! + * @brief This function returns a reference to member twist + * @return Reference to member twist + */ + eProsima_user_DllExport geometry_msgs::msg::Twist& twist(); + /*! + * @brief This function copies the value in member accel + * @param _accel New value to be copied in member accel + */ + eProsima_user_DllExport void accel(const geometry_msgs::msg::Accel& _accel); + + /*! + * @brief This function moves the value in member accel + * @param _accel New value to be moved in member accel + */ + eProsima_user_DllExport void accel(geometry_msgs::msg::Accel&& _accel); + + /*! + * @brief This function returns a constant reference to member accel + * @return Constant reference to member accel + */ + eProsima_user_DllExport const geometry_msgs::msg::Accel& accel() const; + + /*! + * @brief This function returns a reference to member accel + * @return Reference to member accel + */ + eProsima_user_DllExport geometry_msgs::msg::Accel& accel(); + /*! + * @brief This function copies the value in member polygon + * @param _polygon New value to be copied in member polygon + */ + eProsima_user_DllExport void polygon(const geometry_msgs::msg::Polygon& _polygon); + + /*! + * @brief This function moves the value in member polygon + * @param _polygon New value to be moved in member polygon + */ + eProsima_user_DllExport void polygon(geometry_msgs::msg::Polygon&& _polygon); + + /*! + * @brief This function returns a constant reference to member polygon + * @return Constant reference to member polygon + */ + eProsima_user_DllExport const geometry_msgs::msg::Polygon& polygon() const; + + /*! + * @brief This function returns a reference to member polygon + * @return Reference to member polygon + */ + eProsima_user_DllExport geometry_msgs::msg::Polygon& polygon(); + /*! + * @brief This function copies the value in member shape + * @param _shape New value to be copied in member shape + */ + eProsima_user_DllExport void shape(const shape_msgs::msg::SolidPrimitive& _shape); + + /*! + * @brief This function moves the value in member shape + * @param _shape New value to be moved in member shape + */ + eProsima_user_DllExport void shape(shape_msgs::msg::SolidPrimitive&& _shape); + + /*! + * @brief This function returns a constant reference to member shape + * @return Constant reference to member shape + */ + eProsima_user_DllExport const shape_msgs::msg::SolidPrimitive& shape() const; + + /*! + * @brief This function returns a reference to member shape + * @return Reference to member shape + */ + eProsima_user_DllExport shape_msgs::msg::SolidPrimitive& shape(); + /*! + * @brief This function sets a value in member classification + * @param _classification New value for member classification + */ + eProsima_user_DllExport void classification(uint8_t _classification); + + /*! + * @brief This function returns the value of member classification + * @return Value of member classification + */ + eProsima_user_DllExport uint8_t classification() const; + + /*! + * @brief This function returns a reference to member classification + * @return Reference to member classification + */ + eProsima_user_DllExport uint8_t& classification(); + + /*! + * @brief This function sets a value in member classification_certainty + * @param _classification_certainty New value for member classification_certainty + */ + eProsima_user_DllExport void classification_certainty(uint8_t _classification_certainty); + + /*! + * @brief This function returns the value of member classification_certainty + * @return Value of member classification_certainty + */ + eProsima_user_DllExport uint8_t classification_certainty() const; + + /*! + * @brief This function returns a reference to member classification_certainty + * @return Reference to member classification_certainty + */ + eProsima_user_DllExport uint8_t& classification_certainty(); + + /*! + * @brief This function sets a value in member classification_age + * @param _classification_age New value for member classification_age + */ + eProsima_user_DllExport void classification_age(uint32_t _classification_age); + + /*! + * @brief This function returns the value of member classification_age + * @return Value of member classification_age + */ + eProsima_user_DllExport uint32_t classification_age() const; + + /*! + * @brief This function returns a reference to member classification_age + * @return Reference to member classification_age + */ + eProsima_user_DllExport uint32_t& classification_age(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const derived_object_msgs::msg::Object& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + std_msgs::msg::Header m_header; + uint32_t m_id; + uint8_t m_detection_level; + bool m_object_classified; + geometry_msgs::msg::Pose m_pose; + geometry_msgs::msg::Twist m_twist; + geometry_msgs::msg::Accel m_accel; + geometry_msgs::msg::Polygon m_polygon; + shape_msgs::msg::SolidPrimitive m_shape; + uint8_t m_classification; + uint8_t m_classification_certainty; + uint32_t m_classification_age; +}; +} // namespace msg +} // namespace derived_object_msgs + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECT_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArray.cxx b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArray.cxx new file mode 100644 index 00000000000..18c2b27b437 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArray.cxx @@ -0,0 +1,250 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ObjectArray.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "ObjectArray.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +derived_object_msgs::msg::ObjectArray::ObjectArray() +{ + // m_header com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@6db9f5a4 + + // m_objects com.eprosima.idl.parser.typecode.SequenceTypeCode@1ebd319f + + +} + +derived_object_msgs::msg::ObjectArray::~ObjectArray() +{ + +} + +derived_object_msgs::msg::ObjectArray::ObjectArray( + const ObjectArray& x) +{ + m_header = x.m_header; + m_objects = x.m_objects; +} + +derived_object_msgs::msg::ObjectArray::ObjectArray( + ObjectArray&& x) +{ + m_header = std::move(x.m_header); + m_objects = std::move(x.m_objects); +} + +derived_object_msgs::msg::ObjectArray& derived_object_msgs::msg::ObjectArray::operator =( + const ObjectArray& x) +{ + + m_header = x.m_header; + m_objects = x.m_objects; + + return *this; +} + +derived_object_msgs::msg::ObjectArray& derived_object_msgs::msg::ObjectArray::operator =( + ObjectArray&& x) +{ + + m_header = std::move(x.m_header); + m_objects = std::move(x.m_objects); + + return *this; +} + +bool derived_object_msgs::msg::ObjectArray::operator ==( + const ObjectArray& x) const +{ + + return (m_header == x.m_header && m_objects == x.m_objects); +} + +bool derived_object_msgs::msg::ObjectArray::operator !=( + const ObjectArray& x) const +{ + return !(*this == x); +} + +size_t derived_object_msgs::msg::ObjectArray::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getMaxCdrSerializedSize(current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < 100; ++a) + { + current_alignment += derived_object_msgs::msg::Object::getMaxCdrSerializedSize(current_alignment);} + + + return current_alignment - initial_alignment; +} + +size_t derived_object_msgs::msg::ObjectArray::getCdrSerializedSize( + const derived_object_msgs::msg::ObjectArray& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getCdrSerializedSize(data.header(), current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < data.objects().size(); ++a) + { + current_alignment += derived_object_msgs::msg::Object::getCdrSerializedSize(data.objects().at(a), current_alignment);} + + + return current_alignment - initial_alignment; +} + +void derived_object_msgs::msg::ObjectArray::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_header; + scdr << m_objects; + +} + +void derived_object_msgs::msg::ObjectArray::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_header; + dcdr >> m_objects; +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void derived_object_msgs::msg::ObjectArray::header( + const std_msgs::msg::Header& _header) +{ + m_header = _header; +} + +/*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ +void derived_object_msgs::msg::ObjectArray::header( + std_msgs::msg::Header&& _header) +{ + m_header = std::move(_header); +} + +/*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ +const std_msgs::msg::Header& derived_object_msgs::msg::ObjectArray::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& derived_object_msgs::msg::ObjectArray::header() +{ + return m_header; +} +/*! + * @brief This function copies the value in member objects + * @param _objects New value to be copied in member objects + */ +void derived_object_msgs::msg::ObjectArray::objects( + const std::vector& _objects) +{ + m_objects = _objects; +} + +/*! + * @brief This function moves the value in member objects + * @param _objects New value to be moved in member objects + */ +void derived_object_msgs::msg::ObjectArray::objects( + std::vector&& _objects) +{ + m_objects = std::move(_objects); +} + +/*! + * @brief This function returns a constant reference to member objects + * @return Constant reference to member objects + */ +const std::vector& derived_object_msgs::msg::ObjectArray::objects() const +{ + return m_objects; +} + +/*! + * @brief This function returns a reference to member objects + * @return Reference to member objects + */ +std::vector& derived_object_msgs::msg::ObjectArray::objects() +{ + return m_objects; +} + +size_t derived_object_msgs::msg::ObjectArray::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool derived_object_msgs::msg::ObjectArray::isKeyDefined() +{ + return false; +} + +void derived_object_msgs::msg::ObjectArray::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArray.h b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArray.h new file mode 100644 index 00000000000..d4f8f2f0540 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArray.h @@ -0,0 +1,220 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ObjectArray.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTARRAY_H_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTARRAY_H_ + +#include "Object.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(ObjectArray_SOURCE) +#define ObjectArray_DllAPI __declspec(dllexport) +#else +#define ObjectArray_DllAPI __declspec(dllimport) +#endif // ObjectArray_SOURCE +#else +#define ObjectArray_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define ObjectArray_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace derived_object_msgs { +namespace msg { +/*! + * @brief This class represents the structure ObjectArray defined by the user in the IDL file. + * @ingroup OBJECTARRAY + */ +class ObjectArray { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport ObjectArray(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~ObjectArray(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object derived_object_msgs::msg::ObjectArray that will be copied. + */ + eProsima_user_DllExport ObjectArray(const ObjectArray& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object derived_object_msgs::msg::ObjectArray that will be copied. + */ + eProsima_user_DllExport ObjectArray(ObjectArray&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object derived_object_msgs::msg::ObjectArray that will be copied. + */ + eProsima_user_DllExport ObjectArray& operator=(const ObjectArray& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object derived_object_msgs::msg::ObjectArray that will be copied. + */ + eProsima_user_DllExport ObjectArray& operator=(ObjectArray&& x); + + /*! + * @brief Comparison operator. + * @param x derived_object_msgs::msg::ObjectArray object to compare. + */ + eProsima_user_DllExport bool operator==(const ObjectArray& x) const; + + /*! + * @brief Comparison operator. + * @param x derived_object_msgs::msg::ObjectArray object to compare. + */ + eProsima_user_DllExport bool operator!=(const ObjectArray& x) const; + + /*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ + eProsima_user_DllExport void header(const std_msgs::msg::Header& _header); + + /*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ + eProsima_user_DllExport void header(std_msgs::msg::Header&& _header); + + /*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ + eProsima_user_DllExport const std_msgs::msg::Header& header() const; + + /*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ + eProsima_user_DllExport std_msgs::msg::Header& header(); + /*! + * @brief This function copies the value in member objects + * @param _objects New value to be copied in member objects + */ + eProsima_user_DllExport void objects(const std::vector& _objects); + + /*! + * @brief This function moves the value in member objects + * @param _objects New value to be moved in member objects + */ + eProsima_user_DllExport void objects(std::vector&& _objects); + + /*! + * @brief This function returns a constant reference to member objects + * @return Constant reference to member objects + */ + eProsima_user_DllExport const std::vector& objects() const; + + /*! + * @brief This function returns a reference to member objects + * @return Reference to member objects + */ + eProsima_user_DllExport std::vector& objects(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const derived_object_msgs::msg::ObjectArray& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + std_msgs::msg::Header m_header; + std::vector m_objects; +}; +} // namespace msg +} // namespace derived_object_msgs + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTARRAY_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArrayPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArrayPubSubTypes.cxx new file mode 100644 index 00000000000..4d78bea9736 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArrayPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ObjectArrayPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "ObjectArrayPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace derived_object_msgs { + namespace msg { + ObjectArrayPubSubType::ObjectArrayPubSubType() + { + setName("derived_object_msgs::msg::dds_::ObjectArray_"); + auto type_size = ObjectArray::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = ObjectArray::isKeyDefined(); + size_t keyLength = ObjectArray::getKeyMaxCdrSerializedSize() > 16 ? + ObjectArray::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + ObjectArrayPubSubType::~ObjectArrayPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool ObjectArrayPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + ObjectArray* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool ObjectArrayPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + ObjectArray* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function ObjectArrayPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* ObjectArrayPubSubType::createData() + { + return reinterpret_cast(new ObjectArray()); + } + + void ObjectArrayPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool ObjectArrayPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + ObjectArray* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + ObjectArray::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || ObjectArray::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace derived_object_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArrayPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArrayPubSubTypes.h new file mode 100644 index 00000000000..1818dee0a77 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArrayPubSubTypes.h @@ -0,0 +1,91 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ObjectArrayPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTARRAY_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTARRAY_PUBSUBTYPES_H_ + +#include +#include + +#include "ObjectArray.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated ObjectArray is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace derived_object_msgs { +namespace msg { +/*! + * @brief This class represents the TopicDataType of the type ObjectArray defined by the user in the IDL file. + * @ingroup OBJECTARRAY + */ +class ObjectArrayPubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef ObjectArray type; + + eProsima_user_DllExport ObjectArrayPubSubType(); + + eProsima_user_DllExport virtual ~ObjectArrayPubSubType(); + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + (void)memory; + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; +}; +} // namespace msg +} // namespace derived_object_msgs + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTARRAY_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectPubSubTypes.cxx new file mode 100644 index 00000000000..a8f3b22d08a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectPubSubTypes.cxx @@ -0,0 +1,193 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ObjectPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "ObjectPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace derived_object_msgs { + namespace msg { + namespace Object_Constants { + + + + + + + + + + + + + + + + } //End of namespace Object_Constants + ObjectPubSubType::ObjectPubSubType() + { + setName("derived_object_msgs::msg::dds_::Object_"); + auto type_size = Object::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = Object::isKeyDefined(); + size_t keyLength = Object::getKeyMaxCdrSerializedSize() > 16 ? + Object::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + ObjectPubSubType::~ObjectPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool ObjectPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + Object* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool ObjectPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + Object* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function ObjectPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* ObjectPubSubType::createData() + { + return reinterpret_cast(new Object()); + } + + void ObjectPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool ObjectPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + Object* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + Object::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || Object::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace derived_object_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectPubSubTypes.h new file mode 100644 index 00000000000..7cb94c9e9a9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectPubSubTypes.h @@ -0,0 +1,92 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ObjectPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECT_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECT_PUBSUBTYPES_H_ + +#include +#include + +#include "Object.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated Object is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace derived_object_msgs { +namespace msg { +namespace Object_Constants {} +/*! + * @brief This class represents the TopicDataType of the type Object defined by the user in the IDL file. + * @ingroup OBJECT + */ +class ObjectPubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef Object type; + + eProsima_user_DllExport ObjectPubSubType(); + + eProsima_user_DllExport virtual ~ObjectPubSubType(); + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + (void)memory; + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; +}; +} // namespace msg +} // namespace derived_object_msgs + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECT_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovariance.cxx b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovariance.cxx new file mode 100644 index 00000000000..3bdd73f14f7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovariance.cxx @@ -0,0 +1,703 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ObjectWithCovariance.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "ObjectWithCovariance.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + + + + + + + + + +derived_object_msgs::msg::ObjectWithCovariance::ObjectWithCovariance() +{ + // m_header com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@5552768b + + // m_id com.eprosima.idl.parser.typecode.PrimitiveTypeCode@3c947bc5 + m_id = 0; + // m_detection_level com.eprosima.idl.parser.typecode.PrimitiveTypeCode@609db43b + m_detection_level = 0; + // m_object_classified com.eprosima.idl.parser.typecode.PrimitiveTypeCode@55f616cf + m_object_classified = false; + // m_pose com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@1356d4d4 + + // m_twist com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@c03cf28 + + // m_accel com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@1329eff + + // m_polygon com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@6497b078 + + // m_shape com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@41c2284a + + // m_classification com.eprosima.idl.parser.typecode.PrimitiveTypeCode@1fb700ee + m_classification = 0; + // m_classification_certainty com.eprosima.idl.parser.typecode.PrimitiveTypeCode@4f67eb2a + m_classification_certainty = 0; + // m_classification_age com.eprosima.idl.parser.typecode.PrimitiveTypeCode@4a668b6e + m_classification_age = 0; + +} + +derived_object_msgs::msg::ObjectWithCovariance::~ObjectWithCovariance() +{ + + + + + + + + + + + +} + +derived_object_msgs::msg::ObjectWithCovariance::ObjectWithCovariance( + const ObjectWithCovariance& x) +{ + m_header = x.m_header; + m_id = x.m_id; + m_detection_level = x.m_detection_level; + m_object_classified = x.m_object_classified; + m_pose = x.m_pose; + m_twist = x.m_twist; + m_accel = x.m_accel; + m_polygon = x.m_polygon; + m_shape = x.m_shape; + m_classification = x.m_classification; + m_classification_certainty = x.m_classification_certainty; + m_classification_age = x.m_classification_age; +} + +derived_object_msgs::msg::ObjectWithCovariance::ObjectWithCovariance( + ObjectWithCovariance&& x) +{ + m_header = std::move(x.m_header); + m_id = x.m_id; + m_detection_level = x.m_detection_level; + m_object_classified = x.m_object_classified; + m_pose = std::move(x.m_pose); + m_twist = std::move(x.m_twist); + m_accel = std::move(x.m_accel); + m_polygon = std::move(x.m_polygon); + m_shape = std::move(x.m_shape); + m_classification = x.m_classification; + m_classification_certainty = x.m_classification_certainty; + m_classification_age = x.m_classification_age; +} + +derived_object_msgs::msg::ObjectWithCovariance& derived_object_msgs::msg::ObjectWithCovariance::operator =( + const ObjectWithCovariance& x) +{ + + m_header = x.m_header; + m_id = x.m_id; + m_detection_level = x.m_detection_level; + m_object_classified = x.m_object_classified; + m_pose = x.m_pose; + m_twist = x.m_twist; + m_accel = x.m_accel; + m_polygon = x.m_polygon; + m_shape = x.m_shape; + m_classification = x.m_classification; + m_classification_certainty = x.m_classification_certainty; + m_classification_age = x.m_classification_age; + + return *this; +} + +derived_object_msgs::msg::ObjectWithCovariance& derived_object_msgs::msg::ObjectWithCovariance::operator =( + ObjectWithCovariance&& x) +{ + + m_header = std::move(x.m_header); + m_id = x.m_id; + m_detection_level = x.m_detection_level; + m_object_classified = x.m_object_classified; + m_pose = std::move(x.m_pose); + m_twist = std::move(x.m_twist); + m_accel = std::move(x.m_accel); + m_polygon = std::move(x.m_polygon); + m_shape = std::move(x.m_shape); + m_classification = x.m_classification; + m_classification_certainty = x.m_classification_certainty; + m_classification_age = x.m_classification_age; + + return *this; +} + +bool derived_object_msgs::msg::ObjectWithCovariance::operator ==( + const ObjectWithCovariance& x) const +{ + + return (m_header == x.m_header && m_id == x.m_id && m_detection_level == x.m_detection_level && m_object_classified == x.m_object_classified && m_pose == x.m_pose && m_twist == x.m_twist && m_accel == x.m_accel && m_polygon == x.m_polygon && m_shape == x.m_shape && m_classification == x.m_classification && m_classification_certainty == x.m_classification_certainty && m_classification_age == x.m_classification_age); +} + +bool derived_object_msgs::msg::ObjectWithCovariance::operator !=( + const ObjectWithCovariance& x) const +{ + return !(*this == x); +} + +size_t derived_object_msgs::msg::ObjectWithCovariance::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getMaxCdrSerializedSize(current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += geometry_msgs::msg::PoseWithCovariance::getMaxCdrSerializedSize(current_alignment); + current_alignment += geometry_msgs::msg::TwistWithCovariance::getMaxCdrSerializedSize(current_alignment); + current_alignment += geometry_msgs::msg::AccelWithCovariance::getMaxCdrSerializedSize(current_alignment); + current_alignment += geometry_msgs::msg::Polygon::getMaxCdrSerializedSize(current_alignment); + current_alignment += derived_object_msgs::msg::SolidPrimitiveWithCovariance::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + + return current_alignment - initial_alignment; +} + +size_t derived_object_msgs::msg::ObjectWithCovariance::getCdrSerializedSize( + const derived_object_msgs::msg::ObjectWithCovariance& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getCdrSerializedSize(data.header(), current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += geometry_msgs::msg::PoseWithCovariance::getCdrSerializedSize(data.pose(), current_alignment); + current_alignment += geometry_msgs::msg::TwistWithCovariance::getCdrSerializedSize(data.twist(), current_alignment); + current_alignment += geometry_msgs::msg::AccelWithCovariance::getCdrSerializedSize(data.accel(), current_alignment); + current_alignment += geometry_msgs::msg::Polygon::getCdrSerializedSize(data.polygon(), current_alignment); + current_alignment += derived_object_msgs::msg::SolidPrimitiveWithCovariance::getCdrSerializedSize(data.shape(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + + return current_alignment - initial_alignment; +} + +void derived_object_msgs::msg::ObjectWithCovariance::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_header; + scdr << m_id; + scdr << m_detection_level; + scdr << m_object_classified; + scdr << m_pose; + scdr << m_twist; + scdr << m_accel; + scdr << m_polygon; + scdr << m_shape; + scdr << m_classification; + scdr << m_classification_certainty; + scdr << m_classification_age; + +} + +void derived_object_msgs::msg::ObjectWithCovariance::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_header; + dcdr >> m_id; + dcdr >> m_detection_level; + dcdr >> m_object_classified; + dcdr >> m_pose; + dcdr >> m_twist; + dcdr >> m_accel; + dcdr >> m_polygon; + dcdr >> m_shape; + dcdr >> m_classification; + dcdr >> m_classification_certainty; + dcdr >> m_classification_age; +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void derived_object_msgs::msg::ObjectWithCovariance::header( + const std_msgs::msg::Header& _header) +{ + m_header = _header; +} + +/*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ +void derived_object_msgs::msg::ObjectWithCovariance::header( + std_msgs::msg::Header&& _header) +{ + m_header = std::move(_header); +} + +/*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ +const std_msgs::msg::Header& derived_object_msgs::msg::ObjectWithCovariance::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& derived_object_msgs::msg::ObjectWithCovariance::header() +{ + return m_header; +} +/*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ +void derived_object_msgs::msg::ObjectWithCovariance::id( + uint32_t _id) +{ + m_id = _id; +} + +/*! + * @brief This function returns the value of member id + * @return Value of member id + */ +uint32_t derived_object_msgs::msg::ObjectWithCovariance::id() const +{ + return m_id; +} + +/*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ +uint32_t& derived_object_msgs::msg::ObjectWithCovariance::id() +{ + return m_id; +} + +/*! + * @brief This function sets a value in member detection_level + * @param _detection_level New value for member detection_level + */ +void derived_object_msgs::msg::ObjectWithCovariance::detection_level( + uint8_t _detection_level) +{ + m_detection_level = _detection_level; +} + +/*! + * @brief This function returns the value of member detection_level + * @return Value of member detection_level + */ +uint8_t derived_object_msgs::msg::ObjectWithCovariance::detection_level() const +{ + return m_detection_level; +} + +/*! + * @brief This function returns a reference to member detection_level + * @return Reference to member detection_level + */ +uint8_t& derived_object_msgs::msg::ObjectWithCovariance::detection_level() +{ + return m_detection_level; +} + +/*! + * @brief This function sets a value in member object_classified + * @param _object_classified New value for member object_classified + */ +void derived_object_msgs::msg::ObjectWithCovariance::object_classified( + bool _object_classified) +{ + m_object_classified = _object_classified; +} + +/*! + * @brief This function returns the value of member object_classified + * @return Value of member object_classified + */ +bool derived_object_msgs::msg::ObjectWithCovariance::object_classified() const +{ + return m_object_classified; +} + +/*! + * @brief This function returns a reference to member object_classified + * @return Reference to member object_classified + */ +bool& derived_object_msgs::msg::ObjectWithCovariance::object_classified() +{ + return m_object_classified; +} + +/*! + * @brief This function copies the value in member pose + * @param _pose New value to be copied in member pose + */ +void derived_object_msgs::msg::ObjectWithCovariance::pose( + const geometry_msgs::msg::PoseWithCovariance& _pose) +{ + m_pose = _pose; +} + +/*! + * @brief This function moves the value in member pose + * @param _pose New value to be moved in member pose + */ +void derived_object_msgs::msg::ObjectWithCovariance::pose( + geometry_msgs::msg::PoseWithCovariance&& _pose) +{ + m_pose = std::move(_pose); +} + +/*! + * @brief This function returns a constant reference to member pose + * @return Constant reference to member pose + */ +const geometry_msgs::msg::PoseWithCovariance& derived_object_msgs::msg::ObjectWithCovariance::pose() const +{ + return m_pose; +} + +/*! + * @brief This function returns a reference to member pose + * @return Reference to member pose + */ +geometry_msgs::msg::PoseWithCovariance& derived_object_msgs::msg::ObjectWithCovariance::pose() +{ + return m_pose; +} +/*! + * @brief This function copies the value in member twist + * @param _twist New value to be copied in member twist + */ +void derived_object_msgs::msg::ObjectWithCovariance::twist( + const geometry_msgs::msg::TwistWithCovariance& _twist) +{ + m_twist = _twist; +} + +/*! + * @brief This function moves the value in member twist + * @param _twist New value to be moved in member twist + */ +void derived_object_msgs::msg::ObjectWithCovariance::twist( + geometry_msgs::msg::TwistWithCovariance&& _twist) +{ + m_twist = std::move(_twist); +} + +/*! + * @brief This function returns a constant reference to member twist + * @return Constant reference to member twist + */ +const geometry_msgs::msg::TwistWithCovariance& derived_object_msgs::msg::ObjectWithCovariance::twist() const +{ + return m_twist; +} + +/*! + * @brief This function returns a reference to member twist + * @return Reference to member twist + */ +geometry_msgs::msg::TwistWithCovariance& derived_object_msgs::msg::ObjectWithCovariance::twist() +{ + return m_twist; +} +/*! + * @brief This function copies the value in member accel + * @param _accel New value to be copied in member accel + */ +void derived_object_msgs::msg::ObjectWithCovariance::accel( + const geometry_msgs::msg::AccelWithCovariance& _accel) +{ + m_accel = _accel; +} + +/*! + * @brief This function moves the value in member accel + * @param _accel New value to be moved in member accel + */ +void derived_object_msgs::msg::ObjectWithCovariance::accel( + geometry_msgs::msg::AccelWithCovariance&& _accel) +{ + m_accel = std::move(_accel); +} + +/*! + * @brief This function returns a constant reference to member accel + * @return Constant reference to member accel + */ +const geometry_msgs::msg::AccelWithCovariance& derived_object_msgs::msg::ObjectWithCovariance::accel() const +{ + return m_accel; +} + +/*! + * @brief This function returns a reference to member accel + * @return Reference to member accel + */ +geometry_msgs::msg::AccelWithCovariance& derived_object_msgs::msg::ObjectWithCovariance::accel() +{ + return m_accel; +} +/*! + * @brief This function copies the value in member polygon + * @param _polygon New value to be copied in member polygon + */ +void derived_object_msgs::msg::ObjectWithCovariance::polygon( + const geometry_msgs::msg::Polygon& _polygon) +{ + m_polygon = _polygon; +} + +/*! + * @brief This function moves the value in member polygon + * @param _polygon New value to be moved in member polygon + */ +void derived_object_msgs::msg::ObjectWithCovariance::polygon( + geometry_msgs::msg::Polygon&& _polygon) +{ + m_polygon = std::move(_polygon); +} + +/*! + * @brief This function returns a constant reference to member polygon + * @return Constant reference to member polygon + */ +const geometry_msgs::msg::Polygon& derived_object_msgs::msg::ObjectWithCovariance::polygon() const +{ + return m_polygon; +} + +/*! + * @brief This function returns a reference to member polygon + * @return Reference to member polygon + */ +geometry_msgs::msg::Polygon& derived_object_msgs::msg::ObjectWithCovariance::polygon() +{ + return m_polygon; +} +/*! + * @brief This function copies the value in member shape + * @param _shape New value to be copied in member shape + */ +void derived_object_msgs::msg::ObjectWithCovariance::shape( + const derived_object_msgs::msg::SolidPrimitiveWithCovariance& _shape) +{ + m_shape = _shape; +} + +/*! + * @brief This function moves the value in member shape + * @param _shape New value to be moved in member shape + */ +void derived_object_msgs::msg::ObjectWithCovariance::shape( + derived_object_msgs::msg::SolidPrimitiveWithCovariance&& _shape) +{ + m_shape = std::move(_shape); +} + +/*! + * @brief This function returns a constant reference to member shape + * @return Constant reference to member shape + */ +const derived_object_msgs::msg::SolidPrimitiveWithCovariance& derived_object_msgs::msg::ObjectWithCovariance::shape() const +{ + return m_shape; +} + +/*! + * @brief This function returns a reference to member shape + * @return Reference to member shape + */ +derived_object_msgs::msg::SolidPrimitiveWithCovariance& derived_object_msgs::msg::ObjectWithCovariance::shape() +{ + return m_shape; +} +/*! + * @brief This function sets a value in member classification + * @param _classification New value for member classification + */ +void derived_object_msgs::msg::ObjectWithCovariance::classification( + uint8_t _classification) +{ + m_classification = _classification; +} + +/*! + * @brief This function returns the value of member classification + * @return Value of member classification + */ +uint8_t derived_object_msgs::msg::ObjectWithCovariance::classification() const +{ + return m_classification; +} + +/*! + * @brief This function returns a reference to member classification + * @return Reference to member classification + */ +uint8_t& derived_object_msgs::msg::ObjectWithCovariance::classification() +{ + return m_classification; +} + +/*! + * @brief This function sets a value in member classification_certainty + * @param _classification_certainty New value for member classification_certainty + */ +void derived_object_msgs::msg::ObjectWithCovariance::classification_certainty( + uint8_t _classification_certainty) +{ + m_classification_certainty = _classification_certainty; +} + +/*! + * @brief This function returns the value of member classification_certainty + * @return Value of member classification_certainty + */ +uint8_t derived_object_msgs::msg::ObjectWithCovariance::classification_certainty() const +{ + return m_classification_certainty; +} + +/*! + * @brief This function returns a reference to member classification_certainty + * @return Reference to member classification_certainty + */ +uint8_t& derived_object_msgs::msg::ObjectWithCovariance::classification_certainty() +{ + return m_classification_certainty; +} + +/*! + * @brief This function sets a value in member classification_age + * @param _classification_age New value for member classification_age + */ +void derived_object_msgs::msg::ObjectWithCovariance::classification_age( + uint32_t _classification_age) +{ + m_classification_age = _classification_age; +} + +/*! + * @brief This function returns the value of member classification_age + * @return Value of member classification_age + */ +uint32_t derived_object_msgs::msg::ObjectWithCovariance::classification_age() const +{ + return m_classification_age; +} + +/*! + * @brief This function returns a reference to member classification_age + * @return Reference to member classification_age + */ +uint32_t& derived_object_msgs::msg::ObjectWithCovariance::classification_age() +{ + return m_classification_age; +} + + +size_t derived_object_msgs::msg::ObjectWithCovariance::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool derived_object_msgs::msg::ObjectWithCovariance::isKeyDefined() +{ + return false; +} + +void derived_object_msgs::msg::ObjectWithCovariance::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovariance.h b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovariance.h new file mode 100644 index 00000000000..20b7cb1dcf9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovariance.h @@ -0,0 +1,488 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ObjectWithCovariance.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCE_H_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCE_H_ + +#include "geometry_msgs/msg/PoseWithCovariance.h" +#include "geometry_msgs/msg/TwistWithCovariance.h" +#include "SolidPrimitiveWithCovariance.h" +#include "geometry_msgs/msg/Polygon.h" +#include "std_msgs/msg/Header.h" +#include "geometry_msgs/msg/AccelWithCovariance.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(ObjectWithCovariance_SOURCE) +#define ObjectWithCovariance_DllAPI __declspec( dllexport ) +#else +#define ObjectWithCovariance_DllAPI __declspec( dllimport ) +#endif // ObjectWithCovariance_SOURCE +#else +#define ObjectWithCovariance_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define ObjectWithCovariance_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace derived_object_msgs { + namespace msg { + namespace ObjectWithCovariance_Constants { + const uint8_t OBJECT_DETECTED = 0; + const uint8_t OBJECT_TRACKED = 1; + const uint8_t CLASSIFICATION_UNKNOWN = 0; + const uint8_t CLASSIFICATION_UNKNOWN_SMALL = 1; + const uint8_t CLASSIFICATION_UNKNOWN_MEDIUM = 2; + const uint8_t CLASSIFICATION_UNKNOWN_BIG = 3; + const uint8_t CLASSIFICATION_PEDESTRIAN = 4; + const uint8_t CLASSIFICATION_BIKE = 5; + const uint8_t CLASSIFICATION_CAR = 6; + const uint8_t CLASSIFICATION_TRUCK = 7; + const uint8_t CLASSIFICATION_MOTORCYCLE = 8; + const uint8_t CLASSIFICATION_OTHER_VEHICLE = 9; + const uint8_t CLASSIFICATION_BARRIER = 10; + const uint8_t CLASSIFICATION_SIGN = 11; + } // namespace ObjectWithCovariance_Constants + /*! + * @brief This class represents the structure ObjectWithCovariance defined by the user in the IDL file. + * @ingroup OBJECTWITHCOVARIANCE + */ + class ObjectWithCovariance + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport ObjectWithCovariance(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~ObjectWithCovariance(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object derived_object_msgs::msg::ObjectWithCovariance that will be copied. + */ + eProsima_user_DllExport ObjectWithCovariance( + const ObjectWithCovariance& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object derived_object_msgs::msg::ObjectWithCovariance that will be copied. + */ + eProsima_user_DllExport ObjectWithCovariance( + ObjectWithCovariance&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object derived_object_msgs::msg::ObjectWithCovariance that will be copied. + */ + eProsima_user_DllExport ObjectWithCovariance& operator =( + const ObjectWithCovariance& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object derived_object_msgs::msg::ObjectWithCovariance that will be copied. + */ + eProsima_user_DllExport ObjectWithCovariance& operator =( + ObjectWithCovariance&& x); + + /*! + * @brief Comparison operator. + * @param x derived_object_msgs::msg::ObjectWithCovariance object to compare. + */ + eProsima_user_DllExport bool operator ==( + const ObjectWithCovariance& x) const; + + /*! + * @brief Comparison operator. + * @param x derived_object_msgs::msg::ObjectWithCovariance object to compare. + */ + eProsima_user_DllExport bool operator !=( + const ObjectWithCovariance& x) const; + + /*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ + eProsima_user_DllExport void header( + const std_msgs::msg::Header& _header); + + /*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ + eProsima_user_DllExport void header( + std_msgs::msg::Header&& _header); + + /*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ + eProsima_user_DllExport const std_msgs::msg::Header& header() const; + + /*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ + eProsima_user_DllExport std_msgs::msg::Header& header(); + /*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ + eProsima_user_DllExport void id( + uint32_t _id); + + /*! + * @brief This function returns the value of member id + * @return Value of member id + */ + eProsima_user_DllExport uint32_t id() const; + + /*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ + eProsima_user_DllExport uint32_t& id(); + + /*! + * @brief This function sets a value in member detection_level + * @param _detection_level New value for member detection_level + */ + eProsima_user_DllExport void detection_level( + uint8_t _detection_level); + + /*! + * @brief This function returns the value of member detection_level + * @return Value of member detection_level + */ + eProsima_user_DllExport uint8_t detection_level() const; + + /*! + * @brief This function returns a reference to member detection_level + * @return Reference to member detection_level + */ + eProsima_user_DllExport uint8_t& detection_level(); + + /*! + * @brief This function sets a value in member object_classified + * @param _object_classified New value for member object_classified + */ + eProsima_user_DllExport void object_classified( + bool _object_classified); + + /*! + * @brief This function returns the value of member object_classified + * @return Value of member object_classified + */ + eProsima_user_DllExport bool object_classified() const; + + /*! + * @brief This function returns a reference to member object_classified + * @return Reference to member object_classified + */ + eProsima_user_DllExport bool& object_classified(); + + /*! + * @brief This function copies the value in member pose + * @param _pose New value to be copied in member pose + */ + eProsima_user_DllExport void pose( + const geometry_msgs::msg::PoseWithCovariance& _pose); + + /*! + * @brief This function moves the value in member pose + * @param _pose New value to be moved in member pose + */ + eProsima_user_DllExport void pose( + geometry_msgs::msg::PoseWithCovariance&& _pose); + + /*! + * @brief This function returns a constant reference to member pose + * @return Constant reference to member pose + */ + eProsima_user_DllExport const geometry_msgs::msg::PoseWithCovariance& pose() const; + + /*! + * @brief This function returns a reference to member pose + * @return Reference to member pose + */ + eProsima_user_DllExport geometry_msgs::msg::PoseWithCovariance& pose(); + /*! + * @brief This function copies the value in member twist + * @param _twist New value to be copied in member twist + */ + eProsima_user_DllExport void twist( + const geometry_msgs::msg::TwistWithCovariance& _twist); + + /*! + * @brief This function moves the value in member twist + * @param _twist New value to be moved in member twist + */ + eProsima_user_DllExport void twist( + geometry_msgs::msg::TwistWithCovariance&& _twist); + + /*! + * @brief This function returns a constant reference to member twist + * @return Constant reference to member twist + */ + eProsima_user_DllExport const geometry_msgs::msg::TwistWithCovariance& twist() const; + + /*! + * @brief This function returns a reference to member twist + * @return Reference to member twist + */ + eProsima_user_DllExport geometry_msgs::msg::TwistWithCovariance& twist(); + /*! + * @brief This function copies the value in member accel + * @param _accel New value to be copied in member accel + */ + eProsima_user_DllExport void accel( + const geometry_msgs::msg::AccelWithCovariance& _accel); + + /*! + * @brief This function moves the value in member accel + * @param _accel New value to be moved in member accel + */ + eProsima_user_DllExport void accel( + geometry_msgs::msg::AccelWithCovariance&& _accel); + + /*! + * @brief This function returns a constant reference to member accel + * @return Constant reference to member accel + */ + eProsima_user_DllExport const geometry_msgs::msg::AccelWithCovariance& accel() const; + + /*! + * @brief This function returns a reference to member accel + * @return Reference to member accel + */ + eProsima_user_DllExport geometry_msgs::msg::AccelWithCovariance& accel(); + /*! + * @brief This function copies the value in member polygon + * @param _polygon New value to be copied in member polygon + */ + eProsima_user_DllExport void polygon( + const geometry_msgs::msg::Polygon& _polygon); + + /*! + * @brief This function moves the value in member polygon + * @param _polygon New value to be moved in member polygon + */ + eProsima_user_DllExport void polygon( + geometry_msgs::msg::Polygon&& _polygon); + + /*! + * @brief This function returns a constant reference to member polygon + * @return Constant reference to member polygon + */ + eProsima_user_DllExport const geometry_msgs::msg::Polygon& polygon() const; + + /*! + * @brief This function returns a reference to member polygon + * @return Reference to member polygon + */ + eProsima_user_DllExport geometry_msgs::msg::Polygon& polygon(); + /*! + * @brief This function copies the value in member shape + * @param _shape New value to be copied in member shape + */ + eProsima_user_DllExport void shape( + const derived_object_msgs::msg::SolidPrimitiveWithCovariance& _shape); + + /*! + * @brief This function moves the value in member shape + * @param _shape New value to be moved in member shape + */ + eProsima_user_DllExport void shape( + derived_object_msgs::msg::SolidPrimitiveWithCovariance&& _shape); + + /*! + * @brief This function returns a constant reference to member shape + * @return Constant reference to member shape + */ + eProsima_user_DllExport const derived_object_msgs::msg::SolidPrimitiveWithCovariance& shape() const; + + /*! + * @brief This function returns a reference to member shape + * @return Reference to member shape + */ + eProsima_user_DllExport derived_object_msgs::msg::SolidPrimitiveWithCovariance& shape(); + /*! + * @brief This function sets a value in member classification + * @param _classification New value for member classification + */ + eProsima_user_DllExport void classification( + uint8_t _classification); + + /*! + * @brief This function returns the value of member classification + * @return Value of member classification + */ + eProsima_user_DllExport uint8_t classification() const; + + /*! + * @brief This function returns a reference to member classification + * @return Reference to member classification + */ + eProsima_user_DllExport uint8_t& classification(); + + /*! + * @brief This function sets a value in member classification_certainty + * @param _classification_certainty New value for member classification_certainty + */ + eProsima_user_DllExport void classification_certainty( + uint8_t _classification_certainty); + + /*! + * @brief This function returns the value of member classification_certainty + * @return Value of member classification_certainty + */ + eProsima_user_DllExport uint8_t classification_certainty() const; + + /*! + * @brief This function returns a reference to member classification_certainty + * @return Reference to member classification_certainty + */ + eProsima_user_DllExport uint8_t& classification_certainty(); + + /*! + * @brief This function sets a value in member classification_age + * @param _classification_age New value for member classification_age + */ + eProsima_user_DllExport void classification_age( + uint32_t _classification_age); + + /*! + * @brief This function returns the value of member classification_age + * @return Value of member classification_age + */ + eProsima_user_DllExport uint32_t classification_age() const; + + /*! + * @brief This function returns a reference to member classification_age + * @return Reference to member classification_age + */ + eProsima_user_DllExport uint32_t& classification_age(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const derived_object_msgs::msg::ObjectWithCovariance& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std_msgs::msg::Header m_header; + uint32_t m_id; + uint8_t m_detection_level; + bool m_object_classified; + geometry_msgs::msg::PoseWithCovariance m_pose; + geometry_msgs::msg::TwistWithCovariance m_twist; + geometry_msgs::msg::AccelWithCovariance m_accel; + geometry_msgs::msg::Polygon m_polygon; + derived_object_msgs::msg::SolidPrimitiveWithCovariance m_shape; + uint8_t m_classification; + uint8_t m_classification_certainty; + uint32_t m_classification_age; + }; + } // namespace msg +} // namespace derived_object_msgs + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArray.cxx b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArray.cxx new file mode 100644 index 00000000000..1cb2d8f6329 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArray.cxx @@ -0,0 +1,250 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ObjectWithCovarianceArray.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "ObjectWithCovarianceArray.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +derived_object_msgs::msg::ObjectWithCovarianceArray::ObjectWithCovarianceArray() +{ + // m_header com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@6e509ffa + + // m_objects com.eprosima.idl.parser.typecode.SequenceTypeCode@68267da0 + + +} + +derived_object_msgs::msg::ObjectWithCovarianceArray::~ObjectWithCovarianceArray() +{ + +} + +derived_object_msgs::msg::ObjectWithCovarianceArray::ObjectWithCovarianceArray( + const ObjectWithCovarianceArray& x) +{ + m_header = x.m_header; + m_objects = x.m_objects; +} + +derived_object_msgs::msg::ObjectWithCovarianceArray::ObjectWithCovarianceArray( + ObjectWithCovarianceArray&& x) +{ + m_header = std::move(x.m_header); + m_objects = std::move(x.m_objects); +} + +derived_object_msgs::msg::ObjectWithCovarianceArray& derived_object_msgs::msg::ObjectWithCovarianceArray::operator =( + const ObjectWithCovarianceArray& x) +{ + + m_header = x.m_header; + m_objects = x.m_objects; + + return *this; +} + +derived_object_msgs::msg::ObjectWithCovarianceArray& derived_object_msgs::msg::ObjectWithCovarianceArray::operator =( + ObjectWithCovarianceArray&& x) +{ + + m_header = std::move(x.m_header); + m_objects = std::move(x.m_objects); + + return *this; +} + +bool derived_object_msgs::msg::ObjectWithCovarianceArray::operator ==( + const ObjectWithCovarianceArray& x) const +{ + + return (m_header == x.m_header && m_objects == x.m_objects); +} + +bool derived_object_msgs::msg::ObjectWithCovarianceArray::operator !=( + const ObjectWithCovarianceArray& x) const +{ + return !(*this == x); +} + +size_t derived_object_msgs::msg::ObjectWithCovarianceArray::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getMaxCdrSerializedSize(current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < 100; ++a) + { + current_alignment += derived_object_msgs::msg::ObjectWithCovariance::getMaxCdrSerializedSize(current_alignment);} + + + return current_alignment - initial_alignment; +} + +size_t derived_object_msgs::msg::ObjectWithCovarianceArray::getCdrSerializedSize( + const derived_object_msgs::msg::ObjectWithCovarianceArray& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += std_msgs::msg::Header::getCdrSerializedSize(data.header(), current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < data.objects().size(); ++a) + { + current_alignment += derived_object_msgs::msg::ObjectWithCovariance::getCdrSerializedSize(data.objects().at(a), current_alignment);} + + + return current_alignment - initial_alignment; +} + +void derived_object_msgs::msg::ObjectWithCovarianceArray::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_header; + scdr << m_objects; + +} + +void derived_object_msgs::msg::ObjectWithCovarianceArray::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_header; + dcdr >> m_objects; +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void derived_object_msgs::msg::ObjectWithCovarianceArray::header( + const std_msgs::msg::Header& _header) +{ + m_header = _header; +} + +/*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ +void derived_object_msgs::msg::ObjectWithCovarianceArray::header( + std_msgs::msg::Header&& _header) +{ + m_header = std::move(_header); +} + +/*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ +const std_msgs::msg::Header& derived_object_msgs::msg::ObjectWithCovarianceArray::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& derived_object_msgs::msg::ObjectWithCovarianceArray::header() +{ + return m_header; +} +/*! + * @brief This function copies the value in member objects + * @param _objects New value to be copied in member objects + */ +void derived_object_msgs::msg::ObjectWithCovarianceArray::objects( + const std::vector& _objects) +{ + m_objects = _objects; +} + +/*! + * @brief This function moves the value in member objects + * @param _objects New value to be moved in member objects + */ +void derived_object_msgs::msg::ObjectWithCovarianceArray::objects( + std::vector&& _objects) +{ + m_objects = std::move(_objects); +} + +/*! + * @brief This function returns a constant reference to member objects + * @return Constant reference to member objects + */ +const std::vector& derived_object_msgs::msg::ObjectWithCovarianceArray::objects() const +{ + return m_objects; +} + +/*! + * @brief This function returns a reference to member objects + * @return Reference to member objects + */ +std::vector& derived_object_msgs::msg::ObjectWithCovarianceArray::objects() +{ + return m_objects; +} + +size_t derived_object_msgs::msg::ObjectWithCovarianceArray::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool derived_object_msgs::msg::ObjectWithCovarianceArray::isKeyDefined() +{ + return false; +} + +void derived_object_msgs::msg::ObjectWithCovarianceArray::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/types/AckermannDriveStamped.h b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArray.h similarity index 60% rename from LibCarla/source/carla/ros2/types/AckermannDriveStamped.h rename to LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArray.h index 5c3427ea345..e2f2985c278 100644 --- a/LibCarla/source/carla/ros2/types/AckermannDriveStamped.h +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArray.h @@ -13,19 +13,16 @@ // limitations under the License. /*! - * @file AckermannDriveStamped.h + * @file ObjectWithCovarianceArray.h * This header file contains the declaration of the described types in the IDL file. * * This file was generated by the tool gen. */ -#ifndef _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPED_H_ -#define _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPED_H_ +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCEARRAY_H_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCEARRAY_H_ -#include "AckermannDrive.h" -#include "Header.h" - -#include +#include "ObjectWithCovariance.h" #include #include @@ -46,16 +43,16 @@ #if defined(_WIN32) #if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(ACKERMANNDRIVESTAMPED_SOURCE) -#define ACKERMANNDRIVESTAMPED_DllAPI __declspec( dllexport ) +#if defined(ObjectWithCovarianceArray_SOURCE) +#define ObjectWithCovarianceArray_DllAPI __declspec( dllexport ) #else -#define ACKERMANNDRIVESTAMPED_DllAPI __declspec( dllimport ) -#endif // ACKERMANNDRIVESTAMPED_SOURCE +#define ObjectWithCovarianceArray_DllAPI __declspec( dllimport ) +#endif // ObjectWithCovarianceArray_SOURCE #else -#define ACKERMANNDRIVESTAMPED_DllAPI +#define ObjectWithCovarianceArray_DllAPI #endif // EPROSIMA_USER_DLL_EXPORT #else -#define ACKERMANNDRIVESTAMPED_DllAPI +#define ObjectWithCovarianceArray_DllAPI #endif // _WIN32 namespace eprosima { @@ -65,67 +62,67 @@ class Cdr; } // namespace eprosima -namespace ackermann_msgs { +namespace derived_object_msgs { namespace msg { /*! - * @brief This class represents the structure AckermannDriveStamped defined by the user in the IDL file. - * @ingroup AckermannDriveStamped + * @brief This class represents the structure ObjectWithCovarianceArray defined by the user in the IDL file. + * @ingroup OBJECTWITHCOVARIANCEARRAY */ - class AckermannDriveStamped + class ObjectWithCovarianceArray { public: /*! * @brief Default constructor. */ - eProsima_user_DllExport AckermannDriveStamped(); + eProsima_user_DllExport ObjectWithCovarianceArray(); /*! * @brief Default destructor. */ - eProsima_user_DllExport ~AckermannDriveStamped(); + eProsima_user_DllExport ~ObjectWithCovarianceArray(); /*! * @brief Copy constructor. - * @param x Reference to the object ackermann_msgs::msg::AckermannDriveStamped that will be copied. + * @param x Reference to the object derived_object_msgs::msg::ObjectWithCovarianceArray that will be copied. */ - eProsima_user_DllExport AckermannDriveStamped( - const AckermannDriveStamped& x); + eProsima_user_DllExport ObjectWithCovarianceArray( + const ObjectWithCovarianceArray& x); /*! * @brief Move constructor. - * @param x Reference to the object ackermann_msgs::msg::AckermannDriveStamped that will be copied. + * @param x Reference to the object derived_object_msgs::msg::ObjectWithCovarianceArray that will be copied. */ - eProsima_user_DllExport AckermannDriveStamped( - AckermannDriveStamped&& x) noexcept; + eProsima_user_DllExport ObjectWithCovarianceArray( + ObjectWithCovarianceArray&& x); /*! * @brief Copy assignment. - * @param x Reference to the object ackermann_msgs::msg::AckermannDriveStamped that will be copied. + * @param x Reference to the object derived_object_msgs::msg::ObjectWithCovarianceArray that will be copied. */ - eProsima_user_DllExport AckermannDriveStamped& operator =( - const AckermannDriveStamped& x); + eProsima_user_DllExport ObjectWithCovarianceArray& operator =( + const ObjectWithCovarianceArray& x); /*! * @brief Move assignment. - * @param x Reference to the object ackermann_msgs::msg::AckermannDriveStamped that will be copied. + * @param x Reference to the object derived_object_msgs::msg::ObjectWithCovarianceArray that will be copied. */ - eProsima_user_DllExport AckermannDriveStamped& operator =( - AckermannDriveStamped&& x) noexcept; + eProsima_user_DllExport ObjectWithCovarianceArray& operator =( + ObjectWithCovarianceArray&& x); /*! * @brief Comparison operator. - * @param x ackermann_msgs::msg::AckermannDriveStamped object to compare. + * @param x derived_object_msgs::msg::ObjectWithCovarianceArray object to compare. */ eProsima_user_DllExport bool operator ==( - const AckermannDriveStamped& x) const; + const ObjectWithCovarianceArray& x) const; /*! * @brief Comparison operator. - * @param x ackermann_msgs::msg::AckermannDriveStamped object to compare. + * @param x derived_object_msgs::msg::ObjectWithCovarianceArray object to compare. */ eProsima_user_DllExport bool operator !=( - const AckermannDriveStamped& x) const; + const ObjectWithCovarianceArray& x) const; /*! * @brief This function copies the value in member header @@ -153,37 +150,37 @@ namespace ackermann_msgs { */ eProsima_user_DllExport std_msgs::msg::Header& header(); /*! - * @brief This function copies the value in member drive - * @param _drive New value to be copied in member drive + * @brief This function copies the value in member objects + * @param _objects New value to be copied in member objects */ - eProsima_user_DllExport void drive( - const ackermann_msgs::msg::AckermannDrive& _drive); + eProsima_user_DllExport void objects( + const std::vector& _objects); /*! - * @brief This function moves the value in member drive - * @param _drive New value to be moved in member drive + * @brief This function moves the value in member objects + * @param _objects New value to be moved in member objects */ - eProsima_user_DllExport void drive( - ackermann_msgs::msg::AckermannDrive&& _drive); + eProsima_user_DllExport void objects( + std::vector&& _objects); /*! - * @brief This function returns a constant reference to member drive - * @return Constant reference to member drive + * @brief This function returns a constant reference to member objects + * @return Constant reference to member objects */ - eProsima_user_DllExport const ackermann_msgs::msg::AckermannDrive& drive() const; + eProsima_user_DllExport const std::vector& objects() const; /*! - * @brief This function returns a reference to member drive - * @return Reference to member drive + * @brief This function returns a reference to member objects + * @return Reference to member objects */ - eProsima_user_DllExport ackermann_msgs::msg::AckermannDrive& drive(); + eProsima_user_DllExport std::vector& objects(); /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -194,7 +191,7 @@ namespace ackermann_msgs { * @return Serialized size. */ eProsima_user_DllExport static size_t getCdrSerializedSize( - const ackermann_msgs::msg::AckermannDriveStamped& data, + const derived_object_msgs::msg::ObjectWithCovarianceArray& data, size_t current_alignment = 0); @@ -238,11 +235,9 @@ namespace ackermann_msgs { private: std_msgs::msg::Header m_header; - ackermann_msgs::msg::AckermannDrive m_drive; - + std::vector m_objects; }; } // namespace msg -} // namespace ackermann_msgs - -#endif // _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPED_H_ +} // namespace derived_object_msgs +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCEARRAY_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArrayPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArrayPubSubTypes.cxx new file mode 100644 index 00000000000..e0f71c8f0a8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArrayPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ObjectWithCovarianceArrayPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "ObjectWithCovarianceArrayPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace derived_object_msgs { + namespace msg { + ObjectWithCovarianceArrayPubSubType::ObjectWithCovarianceArrayPubSubType() + { + setName("derived_object_msgs::msg::dds_::ObjectWithCovarianceArray_"); + auto type_size = ObjectWithCovarianceArray::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = ObjectWithCovarianceArray::isKeyDefined(); + size_t keyLength = ObjectWithCovarianceArray::getKeyMaxCdrSerializedSize() > 16 ? + ObjectWithCovarianceArray::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + ObjectWithCovarianceArrayPubSubType::~ObjectWithCovarianceArrayPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool ObjectWithCovarianceArrayPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + ObjectWithCovarianceArray* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool ObjectWithCovarianceArrayPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + ObjectWithCovarianceArray* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function ObjectWithCovarianceArrayPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* ObjectWithCovarianceArrayPubSubType::createData() + { + return reinterpret_cast(new ObjectWithCovarianceArray()); + } + + void ObjectWithCovarianceArrayPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool ObjectWithCovarianceArrayPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + ObjectWithCovarianceArray* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + ObjectWithCovarianceArray::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || ObjectWithCovarianceArray::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace derived_object_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArrayPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArrayPubSubTypes.h new file mode 100644 index 00000000000..359c8aa8a63 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArrayPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ObjectWithCovarianceArrayPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCEARRAY_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCEARRAY_PUBSUBTYPES_H_ + +#include +#include + +#include "ObjectWithCovarianceArray.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated ObjectWithCovarianceArray is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace derived_object_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type ObjectWithCovarianceArray defined by the user in the IDL file. + * @ingroup OBJECTWITHCOVARIANCEARRAY + */ + class ObjectWithCovarianceArrayPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef ObjectWithCovarianceArray type; + + eProsima_user_DllExport ObjectWithCovarianceArrayPubSubType(); + + eProsima_user_DllExport virtual ~ObjectWithCovarianceArrayPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCEARRAY_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovariancePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovariancePubSubTypes.cxx new file mode 100644 index 00000000000..d5f4af276e3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovariancePubSubTypes.cxx @@ -0,0 +1,193 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ObjectWithCovariancePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "ObjectWithCovariancePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace derived_object_msgs { + namespace msg { + namespace ObjectWithCovariance_Constants { + + + + + + + + + + + + + + + + } //End of namespace ObjectWithCovariance_Constants + ObjectWithCovariancePubSubType::ObjectWithCovariancePubSubType() + { + setName("derived_object_msgs::msg::dds_::ObjectWithCovariance_"); + auto type_size = ObjectWithCovariance::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = ObjectWithCovariance::isKeyDefined(); + size_t keyLength = ObjectWithCovariance::getKeyMaxCdrSerializedSize() > 16 ? + ObjectWithCovariance::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + ObjectWithCovariancePubSubType::~ObjectWithCovariancePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool ObjectWithCovariancePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + ObjectWithCovariance* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool ObjectWithCovariancePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + ObjectWithCovariance* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function ObjectWithCovariancePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* ObjectWithCovariancePubSubType::createData() + { + return reinterpret_cast(new ObjectWithCovariance()); + } + + void ObjectWithCovariancePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool ObjectWithCovariancePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + ObjectWithCovariance* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + ObjectWithCovariance::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || ObjectWithCovariance::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace derived_object_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovariancePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovariancePubSubTypes.h new file mode 100644 index 00000000000..b29521ecfe9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovariancePubSubTypes.h @@ -0,0 +1,124 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ObjectWithCovariancePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCE_PUBSUBTYPES_H_ + +#include +#include + +#include "ObjectWithCovariance.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated ObjectWithCovariance is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace derived_object_msgs +{ + namespace msg + { + namespace ObjectWithCovariance_Constants + { + + + + + + + + + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type ObjectWithCovariance defined by the user in the IDL file. + * @ingroup OBJECTWITHCOVARIANCE + */ + class ObjectWithCovariancePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef ObjectWithCovariance type; + + eProsima_user_DllExport ObjectWithCovariancePubSubType(); + + eProsima_user_DllExport virtual ~ObjectWithCovariancePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovariance.cxx b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovariance.cxx new file mode 100644 index 00000000000..c147b3ba564 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovariance.cxx @@ -0,0 +1,320 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SolidPrimitiveWithCovariance.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "SolidPrimitiveWithCovariance.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + + + + + + + +derived_object_msgs::msg::SolidPrimitiveWithCovariance::SolidPrimitiveWithCovariance() +{ + // m_type com.eprosima.idl.parser.typecode.PrimitiveTypeCode@48075da3 + m_type = 0; + // m_dimensions com.eprosima.idl.parser.typecode.SequenceTypeCode@68c9133c + + // m_covariance com.eprosima.idl.parser.typecode.SequenceTypeCode@7a35b0f5 + + +} + +derived_object_msgs::msg::SolidPrimitiveWithCovariance::~SolidPrimitiveWithCovariance() +{ + + +} + +derived_object_msgs::msg::SolidPrimitiveWithCovariance::SolidPrimitiveWithCovariance( + const SolidPrimitiveWithCovariance& x) +{ + m_type = x.m_type; + m_dimensions = x.m_dimensions; + m_covariance = x.m_covariance; +} + +derived_object_msgs::msg::SolidPrimitiveWithCovariance::SolidPrimitiveWithCovariance( + SolidPrimitiveWithCovariance&& x) +{ + m_type = x.m_type; + m_dimensions = std::move(x.m_dimensions); + m_covariance = std::move(x.m_covariance); +} + +derived_object_msgs::msg::SolidPrimitiveWithCovariance& derived_object_msgs::msg::SolidPrimitiveWithCovariance::operator =( + const SolidPrimitiveWithCovariance& x) +{ + + m_type = x.m_type; + m_dimensions = x.m_dimensions; + m_covariance = x.m_covariance; + + return *this; +} + +derived_object_msgs::msg::SolidPrimitiveWithCovariance& derived_object_msgs::msg::SolidPrimitiveWithCovariance::operator =( + SolidPrimitiveWithCovariance&& x) +{ + + m_type = x.m_type; + m_dimensions = std::move(x.m_dimensions); + m_covariance = std::move(x.m_covariance); + + return *this; +} + +bool derived_object_msgs::msg::SolidPrimitiveWithCovariance::operator ==( + const SolidPrimitiveWithCovariance& x) const +{ + + return (m_type == x.m_type && m_dimensions == x.m_dimensions && m_covariance == x.m_covariance); +} + +bool derived_object_msgs::msg::SolidPrimitiveWithCovariance::operator !=( + const SolidPrimitiveWithCovariance& x) const +{ + return !(*this == x); +} + +size_t derived_object_msgs::msg::SolidPrimitiveWithCovariance::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + current_alignment += (100 * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + current_alignment += (100 * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + + + return current_alignment - initial_alignment; +} + +size_t derived_object_msgs::msg::SolidPrimitiveWithCovariance::getCdrSerializedSize( + const derived_object_msgs::msg::SolidPrimitiveWithCovariance& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + if (data.dimensions().size() > 0) + { + current_alignment += (data.dimensions().size() * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + } + + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + if (data.covariance().size() > 0) + { + current_alignment += (data.covariance().size() * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + } + + + + + return current_alignment - initial_alignment; +} + +void derived_object_msgs::msg::SolidPrimitiveWithCovariance::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_type; + scdr << m_dimensions; + scdr << m_covariance; + +} + +void derived_object_msgs::msg::SolidPrimitiveWithCovariance::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_type; + dcdr >> m_dimensions; + dcdr >> m_covariance; +} + +/*! + * @brief This function sets a value in member type + * @param _type New value for member type + */ +void derived_object_msgs::msg::SolidPrimitiveWithCovariance::type( + uint8_t _type) +{ + m_type = _type; +} + +/*! + * @brief This function returns the value of member type + * @return Value of member type + */ +uint8_t derived_object_msgs::msg::SolidPrimitiveWithCovariance::type() const +{ + return m_type; +} + +/*! + * @brief This function returns a reference to member type + * @return Reference to member type + */ +uint8_t& derived_object_msgs::msg::SolidPrimitiveWithCovariance::type() +{ + return m_type; +} + +/*! + * @brief This function copies the value in member dimensions + * @param _dimensions New value to be copied in member dimensions + */ +void derived_object_msgs::msg::SolidPrimitiveWithCovariance::dimensions( + const std::vector& _dimensions) +{ + m_dimensions = _dimensions; +} + +/*! + * @brief This function moves the value in member dimensions + * @param _dimensions New value to be moved in member dimensions + */ +void derived_object_msgs::msg::SolidPrimitiveWithCovariance::dimensions( + std::vector&& _dimensions) +{ + m_dimensions = std::move(_dimensions); +} + +/*! + * @brief This function returns a constant reference to member dimensions + * @return Constant reference to member dimensions + */ +const std::vector& derived_object_msgs::msg::SolidPrimitiveWithCovariance::dimensions() const +{ + return m_dimensions; +} + +/*! + * @brief This function returns a reference to member dimensions + * @return Reference to member dimensions + */ +std::vector& derived_object_msgs::msg::SolidPrimitiveWithCovariance::dimensions() +{ + return m_dimensions; +} +/*! + * @brief This function copies the value in member covariance + * @param _covariance New value to be copied in member covariance + */ +void derived_object_msgs::msg::SolidPrimitiveWithCovariance::covariance( + const std::vector& _covariance) +{ + m_covariance = _covariance; +} + +/*! + * @brief This function moves the value in member covariance + * @param _covariance New value to be moved in member covariance + */ +void derived_object_msgs::msg::SolidPrimitiveWithCovariance::covariance( + std::vector&& _covariance) +{ + m_covariance = std::move(_covariance); +} + +/*! + * @brief This function returns a constant reference to member covariance + * @return Constant reference to member covariance + */ +const std::vector& derived_object_msgs::msg::SolidPrimitiveWithCovariance::covariance() const +{ + return m_covariance; +} + +/*! + * @brief This function returns a reference to member covariance + * @return Reference to member covariance + */ +std::vector& derived_object_msgs::msg::SolidPrimitiveWithCovariance::covariance() +{ + return m_covariance; +} + +size_t derived_object_msgs::msg::SolidPrimitiveWithCovariance::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool derived_object_msgs::msg::SolidPrimitiveWithCovariance::isKeyDefined() +{ + return false; +} + +void derived_object_msgs::msg::SolidPrimitiveWithCovariance::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovariance.h b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovariance.h new file mode 100644 index 00000000000..702fe4746ff --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovariance.h @@ -0,0 +1,276 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SolidPrimitiveWithCovariance.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_SOLIDPRIMITIVEWITHCOVARIANCE_H_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_SOLIDPRIMITIVEWITHCOVARIANCE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(SolidPrimitiveWithCovariance_SOURCE) +#define SolidPrimitiveWithCovariance_DllAPI __declspec( dllexport ) +#else +#define SolidPrimitiveWithCovariance_DllAPI __declspec( dllimport ) +#endif // SolidPrimitiveWithCovariance_SOURCE +#else +#define SolidPrimitiveWithCovariance_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define SolidPrimitiveWithCovariance_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace derived_object_msgs { + namespace msg { + namespace SolidPrimitiveWithCovariance_Constants { + const uint8_t BOX = 1; + const uint8_t SPHERE = 2; + const uint8_t CYLINDER = 3; + const uint8_t CONE = 4; + const uint8_t BOX_X = 0; + const uint8_t BOX_Y = 1; + const uint8_t BOX_Z = 2; + const uint8_t SPHERE_RADIUS = 0; + const uint8_t CYLINDER_HEIGHT = 0; + const uint8_t CYLINDER_RADIUS = 1; + const uint8_t CONE_HEIGHT = 0; + const uint8_t CONE_RADIUS = 1; + } // namespace SolidPrimitiveWithCovariance_Constants + /*! + * @brief This class represents the structure SolidPrimitiveWithCovariance defined by the user in the IDL file. + * @ingroup SOLIDPRIMITIVEWITHCOVARIANCE + */ + class SolidPrimitiveWithCovariance + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport SolidPrimitiveWithCovariance(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~SolidPrimitiveWithCovariance(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object derived_object_msgs::msg::SolidPrimitiveWithCovariance that will be copied. + */ + eProsima_user_DllExport SolidPrimitiveWithCovariance( + const SolidPrimitiveWithCovariance& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object derived_object_msgs::msg::SolidPrimitiveWithCovariance that will be copied. + */ + eProsima_user_DllExport SolidPrimitiveWithCovariance( + SolidPrimitiveWithCovariance&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object derived_object_msgs::msg::SolidPrimitiveWithCovariance that will be copied. + */ + eProsima_user_DllExport SolidPrimitiveWithCovariance& operator =( + const SolidPrimitiveWithCovariance& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object derived_object_msgs::msg::SolidPrimitiveWithCovariance that will be copied. + */ + eProsima_user_DllExport SolidPrimitiveWithCovariance& operator =( + SolidPrimitiveWithCovariance&& x); + + /*! + * @brief Comparison operator. + * @param x derived_object_msgs::msg::SolidPrimitiveWithCovariance object to compare. + */ + eProsima_user_DllExport bool operator ==( + const SolidPrimitiveWithCovariance& x) const; + + /*! + * @brief Comparison operator. + * @param x derived_object_msgs::msg::SolidPrimitiveWithCovariance object to compare. + */ + eProsima_user_DllExport bool operator !=( + const SolidPrimitiveWithCovariance& x) const; + + /*! + * @brief This function sets a value in member type + * @param _type New value for member type + */ + eProsima_user_DllExport void type( + uint8_t _type); + + /*! + * @brief This function returns the value of member type + * @return Value of member type + */ + eProsima_user_DllExport uint8_t type() const; + + /*! + * @brief This function returns a reference to member type + * @return Reference to member type + */ + eProsima_user_DllExport uint8_t& type(); + + /*! + * @brief This function copies the value in member dimensions + * @param _dimensions New value to be copied in member dimensions + */ + eProsima_user_DllExport void dimensions( + const std::vector& _dimensions); + + /*! + * @brief This function moves the value in member dimensions + * @param _dimensions New value to be moved in member dimensions + */ + eProsima_user_DllExport void dimensions( + std::vector&& _dimensions); + + /*! + * @brief This function returns a constant reference to member dimensions + * @return Constant reference to member dimensions + */ + eProsima_user_DllExport const std::vector& dimensions() const; + + /*! + * @brief This function returns a reference to member dimensions + * @return Reference to member dimensions + */ + eProsima_user_DllExport std::vector& dimensions(); + /*! + * @brief This function copies the value in member covariance + * @param _covariance New value to be copied in member covariance + */ + eProsima_user_DllExport void covariance( + const std::vector& _covariance); + + /*! + * @brief This function moves the value in member covariance + * @param _covariance New value to be moved in member covariance + */ + eProsima_user_DllExport void covariance( + std::vector&& _covariance); + + /*! + * @brief This function returns a constant reference to member covariance + * @return Constant reference to member covariance + */ + eProsima_user_DllExport const std::vector& covariance() const; + + /*! + * @brief This function returns a reference to member covariance + * @return Reference to member covariance + */ + eProsima_user_DllExport std::vector& covariance(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const derived_object_msgs::msg::SolidPrimitiveWithCovariance& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_type; + std::vector m_dimensions; + std::vector m_covariance; + }; + } // namespace msg +} // namespace derived_object_msgs + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_SOLIDPRIMITIVEWITHCOVARIANCE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovariancePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovariancePubSubTypes.cxx new file mode 100644 index 00000000000..0c23b089740 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovariancePubSubTypes.cxx @@ -0,0 +1,191 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SolidPrimitiveWithCovariancePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "SolidPrimitiveWithCovariancePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace derived_object_msgs { + namespace msg { + namespace SolidPrimitiveWithCovariance_Constants { + + + + + + + + + + + + + + } //End of namespace SolidPrimitiveWithCovariance_Constants + SolidPrimitiveWithCovariancePubSubType::SolidPrimitiveWithCovariancePubSubType() + { + setName("derived_object_msgs::msg::dds_::SolidPrimitiveWithCovariance_"); + auto type_size = SolidPrimitiveWithCovariance::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = SolidPrimitiveWithCovariance::isKeyDefined(); + size_t keyLength = SolidPrimitiveWithCovariance::getKeyMaxCdrSerializedSize() > 16 ? + SolidPrimitiveWithCovariance::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + SolidPrimitiveWithCovariancePubSubType::~SolidPrimitiveWithCovariancePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool SolidPrimitiveWithCovariancePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + SolidPrimitiveWithCovariance* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool SolidPrimitiveWithCovariancePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + SolidPrimitiveWithCovariance* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function SolidPrimitiveWithCovariancePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* SolidPrimitiveWithCovariancePubSubType::createData() + { + return reinterpret_cast(new SolidPrimitiveWithCovariance()); + } + + void SolidPrimitiveWithCovariancePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool SolidPrimitiveWithCovariancePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + SolidPrimitiveWithCovariance* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + SolidPrimitiveWithCovariance::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || SolidPrimitiveWithCovariance::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace derived_object_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovariancePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovariancePubSubTypes.h new file mode 100644 index 00000000000..b63468cab18 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovariancePubSubTypes.h @@ -0,0 +1,122 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SolidPrimitiveWithCovariancePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_SOLIDPRIMITIVEWITHCOVARIANCE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_SOLIDPRIMITIVEWITHCOVARIANCE_PUBSUBTYPES_H_ + +#include +#include + +#include "SolidPrimitiveWithCovariance.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated SolidPrimitiveWithCovariance is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace derived_object_msgs +{ + namespace msg + { + namespace SolidPrimitiveWithCovariance_Constants + { + + + + + + + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type SolidPrimitiveWithCovariance defined by the user in the IDL file. + * @ingroup SOLIDPRIMITIVEWITHCOVARIANCE + */ + class SolidPrimitiveWithCovariancePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef SolidPrimitiveWithCovariance type; + + eProsima_user_DllExport SolidPrimitiveWithCovariancePubSubType(); + + eProsima_user_DllExport virtual ~SolidPrimitiveWithCovariancePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_SOLIDPRIMITIVEWITHCOVARIANCE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValue.cxx b/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValue.cxx new file mode 100644 index 00000000000..d6c663435b8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValue.cxx @@ -0,0 +1,242 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file KeyValue.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "KeyValue.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +diagnostic_msgs::msg::KeyValue::KeyValue() +{ + // m_key com.eprosima.idl.parser.typecode.StringTypeCode@77888435 + m_key =""; + // m_value com.eprosima.idl.parser.typecode.StringTypeCode@73a1e9a9 + m_value =""; + +} + +diagnostic_msgs::msg::KeyValue::~KeyValue() +{ + +} + +diagnostic_msgs::msg::KeyValue::KeyValue( + const KeyValue& x) +{ + m_key = x.m_key; + m_value = x.m_value; +} + +diagnostic_msgs::msg::KeyValue::KeyValue( + KeyValue&& x) +{ + m_key = std::move(x.m_key); + m_value = std::move(x.m_value); +} + +diagnostic_msgs::msg::KeyValue& diagnostic_msgs::msg::KeyValue::operator =( + const KeyValue& x) +{ + + m_key = x.m_key; + m_value = x.m_value; + + return *this; +} + +diagnostic_msgs::msg::KeyValue& diagnostic_msgs::msg::KeyValue::operator =( + KeyValue&& x) +{ + + m_key = std::move(x.m_key); + m_value = std::move(x.m_value); + + return *this; +} + +bool diagnostic_msgs::msg::KeyValue::operator ==( + const KeyValue& x) const +{ + + return (m_key == x.m_key && m_value == x.m_value); +} + +bool diagnostic_msgs::msg::KeyValue::operator !=( + const KeyValue& x) const +{ + return !(*this == x); +} + +size_t diagnostic_msgs::msg::KeyValue::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + + + return current_alignment - initial_alignment; +} + +size_t diagnostic_msgs::msg::KeyValue::getCdrSerializedSize( + const diagnostic_msgs::msg::KeyValue& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.key().size() + 1; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.value().size() + 1; + + + return current_alignment - initial_alignment; +} + +void diagnostic_msgs::msg::KeyValue::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_key; + scdr << m_value; + +} + +void diagnostic_msgs::msg::KeyValue::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_key; + dcdr >> m_value; +} + +/*! + * @brief This function copies the value in member key + * @param _key New value to be copied in member key + */ +void diagnostic_msgs::msg::KeyValue::key( + const std::string& _key) +{ + m_key = _key; +} + +/*! + * @brief This function moves the value in member key + * @param _key New value to be moved in member key + */ +void diagnostic_msgs::msg::KeyValue::key( + std::string&& _key) +{ + m_key = std::move(_key); +} + +/*! + * @brief This function returns a constant reference to member key + * @return Constant reference to member key + */ +const std::string& diagnostic_msgs::msg::KeyValue::key() const +{ + return m_key; +} + +/*! + * @brief This function returns a reference to member key + * @return Reference to member key + */ +std::string& diagnostic_msgs::msg::KeyValue::key() +{ + return m_key; +} +/*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ +void diagnostic_msgs::msg::KeyValue::value( + const std::string& _value) +{ + m_value = _value; +} + +/*! + * @brief This function moves the value in member value + * @param _value New value to be moved in member value + */ +void diagnostic_msgs::msg::KeyValue::value( + std::string&& _value) +{ + m_value = std::move(_value); +} + +/*! + * @brief This function returns a constant reference to member value + * @return Constant reference to member value + */ +const std::string& diagnostic_msgs::msg::KeyValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +std::string& diagnostic_msgs::msg::KeyValue::value() +{ + return m_value; +} + +size_t diagnostic_msgs::msg::KeyValue::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool diagnostic_msgs::msg::KeyValue::isKeyDefined() +{ + return false; +} + +void diagnostic_msgs::msg::KeyValue::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValue.h b/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValue.h new file mode 100644 index 00000000000..4d5ecac164d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValue.h @@ -0,0 +1,218 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file KeyValue.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_DIAGNOSTIC_MSGS_MSG_KEYVALUE_H_ +#define _FAST_DDS_GENERATED_DIAGNOSTIC_MSGS_MSG_KEYVALUE_H_ + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(KeyValue_SOURCE) +#define KeyValue_DllAPI __declspec(dllexport) +#else +#define KeyValue_DllAPI __declspec(dllimport) +#endif // KeyValue_SOURCE +#else +#define KeyValue_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define KeyValue_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace diagnostic_msgs { +namespace msg { +/*! + * @brief This class represents the structure KeyValue defined by the user in the IDL file. + * @ingroup KEYVALUE + */ +class KeyValue { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport KeyValue(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~KeyValue(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object diagnostic_msgs::msg::KeyValue that will be copied. + */ + eProsima_user_DllExport KeyValue(const KeyValue& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object diagnostic_msgs::msg::KeyValue that will be copied. + */ + eProsima_user_DllExport KeyValue(KeyValue&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object diagnostic_msgs::msg::KeyValue that will be copied. + */ + eProsima_user_DllExport KeyValue& operator=(const KeyValue& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object diagnostic_msgs::msg::KeyValue that will be copied. + */ + eProsima_user_DllExport KeyValue& operator=(KeyValue&& x); + + /*! + * @brief Comparison operator. + * @param x diagnostic_msgs::msg::KeyValue object to compare. + */ + eProsima_user_DllExport bool operator==(const KeyValue& x) const; + + /*! + * @brief Comparison operator. + * @param x diagnostic_msgs::msg::KeyValue object to compare. + */ + eProsima_user_DllExport bool operator!=(const KeyValue& x) const; + + /*! + * @brief This function copies the value in member key + * @param _key New value to be copied in member key + */ + eProsima_user_DllExport void key(const std::string& _key); + + /*! + * @brief This function moves the value in member key + * @param _key New value to be moved in member key + */ + eProsima_user_DllExport void key(std::string&& _key); + + /*! + * @brief This function returns a constant reference to member key + * @return Constant reference to member key + */ + eProsima_user_DllExport const std::string& key() const; + + /*! + * @brief This function returns a reference to member key + * @return Reference to member key + */ + eProsima_user_DllExport std::string& key(); + /*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ + eProsima_user_DllExport void value(const std::string& _value); + + /*! + * @brief This function moves the value in member value + * @param _value New value to be moved in member value + */ + eProsima_user_DllExport void value(std::string&& _value); + + /*! + * @brief This function returns a constant reference to member value + * @return Constant reference to member value + */ + eProsima_user_DllExport const std::string& value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport std::string& value(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const diagnostic_msgs::msg::KeyValue& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + std::string m_key; + std::string m_value; +}; +} // namespace msg +} // namespace diagnostic_msgs + +#endif // _FAST_DDS_GENERATED_DIAGNOSTIC_MSGS_MSG_KEYVALUE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValuePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValuePubSubTypes.cxx new file mode 100644 index 00000000000..1ef029471c8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValuePubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file KeyValuePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "KeyValuePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace diagnostic_msgs { + namespace msg { + KeyValuePubSubType::KeyValuePubSubType() + { + setName("diagnostic_msgs::msg::dds_::KeyValue_"); + auto type_size = KeyValue::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = KeyValue::isKeyDefined(); + size_t keyLength = KeyValue::getKeyMaxCdrSerializedSize() > 16 ? + KeyValue::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + KeyValuePubSubType::~KeyValuePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool KeyValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + KeyValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool KeyValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + KeyValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function KeyValuePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* KeyValuePubSubType::createData() + { + return reinterpret_cast(new KeyValue()); + } + + void KeyValuePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool KeyValuePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + KeyValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + KeyValue::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || KeyValue::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace diagnostic_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValuePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValuePubSubTypes.h new file mode 100644 index 00000000000..c8294a09b09 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValuePubSubTypes.h @@ -0,0 +1,91 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file KeyValuePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_DIAGNOSTIC_MSGS_MSG_KEYVALUE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_DIAGNOSTIC_MSGS_MSG_KEYVALUE_PUBSUBTYPES_H_ + +#include +#include + +#include "KeyValue.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated KeyValue is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace diagnostic_msgs { +namespace msg { +/*! + * @brief This class represents the TopicDataType of the type KeyValue defined by the user in the IDL file. + * @ingroup KEYVALUE + */ +class KeyValuePubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef KeyValue type; + + eProsima_user_DllExport KeyValuePubSubType(); + + eProsima_user_DllExport virtual ~KeyValuePubSubType(); + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + (void)memory; + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; +}; +} // namespace msg +} // namespace diagnostic_msgs + +#endif // _FAST_DDS_GENERATED_DIAGNOSTIC_MSGS_MSG_KEYVALUE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidence.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidence.cxx new file mode 100644 index 00000000000..01057ba7cc3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidence.cxx @@ -0,0 +1,189 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AccelerationConfidence.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "AccelerationConfidence.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + +etsi_its_cam_msgs::msg::AccelerationConfidence::AccelerationConfidence() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@488b50ec + m_value = 0; + +} + +etsi_its_cam_msgs::msg::AccelerationConfidence::~AccelerationConfidence() +{ +} + +etsi_its_cam_msgs::msg::AccelerationConfidence::AccelerationConfidence( + const AccelerationConfidence& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::AccelerationConfidence::AccelerationConfidence( + AccelerationConfidence&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::AccelerationConfidence& etsi_its_cam_msgs::msg::AccelerationConfidence::operator =( + const AccelerationConfidence& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::AccelerationConfidence& etsi_its_cam_msgs::msg::AccelerationConfidence::operator =( + AccelerationConfidence&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::AccelerationConfidence::operator ==( + const AccelerationConfidence& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::AccelerationConfidence::operator !=( + const AccelerationConfidence& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::AccelerationConfidence::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::AccelerationConfidence::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::AccelerationConfidence& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::AccelerationConfidence::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::AccelerationConfidence::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::AccelerationConfidence::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::AccelerationConfidence::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::AccelerationConfidence::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::AccelerationConfidence::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::AccelerationConfidence::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::AccelerationConfidence::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidence.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidence.h new file mode 100644 index 00000000000..77772770cf0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidence.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AccelerationConfidence.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONFIDENCE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONFIDENCE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(AccelerationConfidence_SOURCE) +#define AccelerationConfidence_DllAPI __declspec( dllexport ) +#else +#define AccelerationConfidence_DllAPI __declspec( dllimport ) +#endif // AccelerationConfidence_SOURCE +#else +#define AccelerationConfidence_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define AccelerationConfidence_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace AccelerationConfidence_Constants { + const uint8_t MIN = 0; + const uint8_t MAX = 102; + const uint8_t POINT_ONE_METER_PER_SEC_SQUARED = 1; + const uint8_t OUT_OF_RANGE = 101; + const uint8_t UNAVAILABLE = 102; + } // namespace AccelerationConfidence_Constants + /*! + * @brief This class represents the structure AccelerationConfidence defined by the user in the IDL file. + * @ingroup ACCELERATIONCONFIDENCE + */ + class AccelerationConfidence + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport AccelerationConfidence(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~AccelerationConfidence(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::AccelerationConfidence that will be copied. + */ + eProsima_user_DllExport AccelerationConfidence( + const AccelerationConfidence& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::AccelerationConfidence that will be copied. + */ + eProsima_user_DllExport AccelerationConfidence( + AccelerationConfidence&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::AccelerationConfidence that will be copied. + */ + eProsima_user_DllExport AccelerationConfidence& operator =( + const AccelerationConfidence& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::AccelerationConfidence that will be copied. + */ + eProsima_user_DllExport AccelerationConfidence& operator =( + AccelerationConfidence&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::AccelerationConfidence object to compare. + */ + eProsima_user_DllExport bool operator ==( + const AccelerationConfidence& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::AccelerationConfidence object to compare. + */ + eProsima_user_DllExport bool operator !=( + const AccelerationConfidence& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::AccelerationConfidence& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONFIDENCE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidencePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidencePubSubTypes.cxx new file mode 100644 index 00000000000..364f536aaea --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidencePubSubTypes.cxx @@ -0,0 +1,184 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AccelerationConfidencePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "AccelerationConfidencePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace AccelerationConfidence_Constants { + + + + + + + } //End of namespace AccelerationConfidence_Constants + AccelerationConfidencePubSubType::AccelerationConfidencePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::AccelerationConfidence_"); + auto type_size = AccelerationConfidence::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = AccelerationConfidence::isKeyDefined(); + size_t keyLength = AccelerationConfidence::getKeyMaxCdrSerializedSize() > 16 ? + AccelerationConfidence::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + AccelerationConfidencePubSubType::~AccelerationConfidencePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool AccelerationConfidencePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + AccelerationConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool AccelerationConfidencePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + AccelerationConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function AccelerationConfidencePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* AccelerationConfidencePubSubType::createData() + { + return reinterpret_cast(new AccelerationConfidence()); + } + + void AccelerationConfidencePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool AccelerationConfidencePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + AccelerationConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + AccelerationConfidence::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || AccelerationConfidence::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidencePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidencePubSubTypes.h new file mode 100644 index 00000000000..d8b8905bb0c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidencePubSubTypes.h @@ -0,0 +1,115 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AccelerationConfidencePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONFIDENCE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONFIDENCE_PUBSUBTYPES_H_ + +#include +#include + +#include "AccelerationConfidence.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated AccelerationConfidence is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace AccelerationConfidence_Constants + { + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type AccelerationConfidence defined by the user in the IDL file. + * @ingroup ACCELERATIONCONFIDENCE + */ + class AccelerationConfidencePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef AccelerationConfidence type; + + eProsima_user_DllExport AccelerationConfidencePubSubType(); + + eProsima_user_DllExport virtual ~AccelerationConfidencePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) AccelerationConfidence(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONFIDENCE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControl.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControl.cxx new file mode 100644 index 00000000000..c383be637fc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControl.cxx @@ -0,0 +1,255 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AccelerationControl.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "AccelerationControl.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + + + +etsi_its_cam_msgs::msg::AccelerationControl::AccelerationControl() +{ + // m_value com.eprosima.idl.parser.typecode.SequenceTypeCode@7fab4be7 + + // m_bits_unused com.eprosima.idl.parser.typecode.PrimitiveTypeCode@a64e035 + m_bits_unused = 0; + +} + +etsi_its_cam_msgs::msg::AccelerationControl::~AccelerationControl() +{ + +} + +etsi_its_cam_msgs::msg::AccelerationControl::AccelerationControl( + const AccelerationControl& x) +{ + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; +} + +etsi_its_cam_msgs::msg::AccelerationControl::AccelerationControl( + AccelerationControl&& x) +{ + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; +} + +etsi_its_cam_msgs::msg::AccelerationControl& etsi_its_cam_msgs::msg::AccelerationControl::operator =( + const AccelerationControl& x) +{ + + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; + + return *this; +} + +etsi_its_cam_msgs::msg::AccelerationControl& etsi_its_cam_msgs::msg::AccelerationControl::operator =( + AccelerationControl&& x) +{ + + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; + + return *this; +} + +bool etsi_its_cam_msgs::msg::AccelerationControl::operator ==( + const AccelerationControl& x) const +{ + + return (m_value == x.m_value && m_bits_unused == x.m_bits_unused); +} + +bool etsi_its_cam_msgs::msg::AccelerationControl::operator !=( + const AccelerationControl& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::AccelerationControl::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + current_alignment += (100 * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::AccelerationControl::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::AccelerationControl& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + if (data.value().size() > 0) + { + current_alignment += (data.value().size() * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + } + + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::AccelerationControl::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + scdr << m_bits_unused; + +} + +void etsi_its_cam_msgs::msg::AccelerationControl::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; + dcdr >> m_bits_unused; +} + +/*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ +void etsi_its_cam_msgs::msg::AccelerationControl::value( + const std::vector& _value) +{ + m_value = _value; +} + +/*! + * @brief This function moves the value in member value + * @param _value New value to be moved in member value + */ +void etsi_its_cam_msgs::msg::AccelerationControl::value( + std::vector&& _value) +{ + m_value = std::move(_value); +} + +/*! + * @brief This function returns a constant reference to member value + * @return Constant reference to member value + */ +const std::vector& etsi_its_cam_msgs::msg::AccelerationControl::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +std::vector& etsi_its_cam_msgs::msg::AccelerationControl::value() +{ + return m_value; +} +/*! + * @brief This function sets a value in member bits_unused + * @param _bits_unused New value for member bits_unused + */ +void etsi_its_cam_msgs::msg::AccelerationControl::bits_unused( + uint8_t _bits_unused) +{ + m_bits_unused = _bits_unused; +} + +/*! + * @brief This function returns the value of member bits_unused + * @return Value of member bits_unused + */ +uint8_t etsi_its_cam_msgs::msg::AccelerationControl::bits_unused() const +{ + return m_bits_unused; +} + +/*! + * @brief This function returns a reference to member bits_unused + * @return Reference to member bits_unused + */ +uint8_t& etsi_its_cam_msgs::msg::AccelerationControl::bits_unused() +{ + return m_bits_unused; +} + + +size_t etsi_its_cam_msgs::msg::AccelerationControl::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::AccelerationControl::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::AccelerationControl::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControl.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControl.h new file mode 100644 index 00000000000..752a9644c16 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControl.h @@ -0,0 +1,246 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AccelerationControl.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONTROL_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONTROL_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(AccelerationControl_SOURCE) +#define AccelerationControl_DllAPI __declspec( dllexport ) +#else +#define AccelerationControl_DllAPI __declspec( dllimport ) +#endif // AccelerationControl_SOURCE +#else +#define AccelerationControl_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define AccelerationControl_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace AccelerationControl_Constants { + const uint8_t SIZE_BITS = 7; + const uint8_t BIT_INDEX_BRAKE_PEDAL_ENGAGED = 0; + const uint8_t BIT_INDEX_GAS_PEDAL_ENGAGED = 1; + const uint8_t BIT_INDEX_EMERGENCY_BRAKE_ENGAGED = 2; + const uint8_t BIT_INDEX_COLLISION_WARNING_ENGAGED = 3; + const uint8_t BIT_INDEX_ACC_ENGAGED = 4; + const uint8_t BIT_INDEX_CRUISE_CONTROL_ENGAGED = 5; + const uint8_t BIT_INDEX_SPEED_LIMITER_ENGAGED = 6; + } // namespace AccelerationControl_Constants + /*! + * @brief This class represents the structure AccelerationControl defined by the user in the IDL file. + * @ingroup ACCELERATIONCONTROL + */ + class AccelerationControl + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport AccelerationControl(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~AccelerationControl(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::AccelerationControl that will be copied. + */ + eProsima_user_DllExport AccelerationControl( + const AccelerationControl& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::AccelerationControl that will be copied. + */ + eProsima_user_DllExport AccelerationControl( + AccelerationControl&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::AccelerationControl that will be copied. + */ + eProsima_user_DllExport AccelerationControl& operator =( + const AccelerationControl& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::AccelerationControl that will be copied. + */ + eProsima_user_DllExport AccelerationControl& operator =( + AccelerationControl&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::AccelerationControl object to compare. + */ + eProsima_user_DllExport bool operator ==( + const AccelerationControl& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::AccelerationControl object to compare. + */ + eProsima_user_DllExport bool operator !=( + const AccelerationControl& x) const; + + /*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ + eProsima_user_DllExport void value( + const std::vector& _value); + + /*! + * @brief This function moves the value in member value + * @param _value New value to be moved in member value + */ + eProsima_user_DllExport void value( + std::vector&& _value); + + /*! + * @brief This function returns a constant reference to member value + * @return Constant reference to member value + */ + eProsima_user_DllExport const std::vector& value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport std::vector& value(); + /*! + * @brief This function sets a value in member bits_unused + * @param _bits_unused New value for member bits_unused + */ + eProsima_user_DllExport void bits_unused( + uint8_t _bits_unused); + + /*! + * @brief This function returns the value of member bits_unused + * @return Value of member bits_unused + */ + eProsima_user_DllExport uint8_t bits_unused() const; + + /*! + * @brief This function returns a reference to member bits_unused + * @return Reference to member bits_unused + */ + eProsima_user_DllExport uint8_t& bits_unused(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::AccelerationControl& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std::vector m_value; + uint8_t m_bits_unused; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONTROL_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControlPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControlPubSubTypes.cxx new file mode 100644 index 00000000000..5c820a04f00 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControlPubSubTypes.cxx @@ -0,0 +1,187 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AccelerationControlPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "AccelerationControlPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace AccelerationControl_Constants { + + + + + + + + + + } //End of namespace AccelerationControl_Constants + AccelerationControlPubSubType::AccelerationControlPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::AccelerationControl_"); + auto type_size = AccelerationControl::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = AccelerationControl::isKeyDefined(); + size_t keyLength = AccelerationControl::getKeyMaxCdrSerializedSize() > 16 ? + AccelerationControl::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + AccelerationControlPubSubType::~AccelerationControlPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool AccelerationControlPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + AccelerationControl* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool AccelerationControlPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + AccelerationControl* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function AccelerationControlPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* AccelerationControlPubSubType::createData() + { + return reinterpret_cast(new AccelerationControl()); + } + + void AccelerationControlPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool AccelerationControlPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + AccelerationControl* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + AccelerationControl::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || AccelerationControl::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControlPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControlPubSubTypes.h new file mode 100644 index 00000000000..e3209bc69bf --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControlPubSubTypes.h @@ -0,0 +1,118 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AccelerationControlPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONTROL_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONTROL_PUBSUBTYPES_H_ + +#include +#include + +#include "AccelerationControl.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated AccelerationControl is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace AccelerationControl_Constants + { + + + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type AccelerationControl defined by the user in the IDL file. + * @ingroup ACCELERATIONCONTROL + */ + class AccelerationControlPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef AccelerationControl type; + + eProsima_user_DllExport AccelerationControlPubSubType(); + + eProsima_user_DllExport virtual ~AccelerationControlPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONTROL_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Altitude.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Altitude.cxx new file mode 100644 index 00000000000..46655cfa36f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Altitude.cxx @@ -0,0 +1,238 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Altitude.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Altitude.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::Altitude::Altitude() +{ + // m_altitude_value com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@476a736d + + // m_altitude_confidence com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@5f80fa43 + + +} + +etsi_its_cam_msgs::msg::Altitude::~Altitude() +{ + +} + +etsi_its_cam_msgs::msg::Altitude::Altitude( + const Altitude& x) +{ + m_altitude_value = x.m_altitude_value; + m_altitude_confidence = x.m_altitude_confidence; +} + +etsi_its_cam_msgs::msg::Altitude::Altitude( + Altitude&& x) +{ + m_altitude_value = std::move(x.m_altitude_value); + m_altitude_confidence = std::move(x.m_altitude_confidence); +} + +etsi_its_cam_msgs::msg::Altitude& etsi_its_cam_msgs::msg::Altitude::operator =( + const Altitude& x) +{ + + m_altitude_value = x.m_altitude_value; + m_altitude_confidence = x.m_altitude_confidence; + + return *this; +} + +etsi_its_cam_msgs::msg::Altitude& etsi_its_cam_msgs::msg::Altitude::operator =( + Altitude&& x) +{ + + m_altitude_value = std::move(x.m_altitude_value); + m_altitude_confidence = std::move(x.m_altitude_confidence); + + return *this; +} + +bool etsi_its_cam_msgs::msg::Altitude::operator ==( + const Altitude& x) const +{ + + return (m_altitude_value == x.m_altitude_value && m_altitude_confidence == x.m_altitude_confidence); +} + +bool etsi_its_cam_msgs::msg::Altitude::operator !=( + const Altitude& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::Altitude::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::AltitudeValue::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::AltitudeConfidence::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::Altitude::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::Altitude& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::AltitudeValue::getCdrSerializedSize(data.altitude_value(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::AltitudeConfidence::getCdrSerializedSize(data.altitude_confidence(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::Altitude::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_altitude_value; + scdr << m_altitude_confidence; + +} + +void etsi_its_cam_msgs::msg::Altitude::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_altitude_value; + dcdr >> m_altitude_confidence; +} + +/*! + * @brief This function copies the value in member altitude_value + * @param _altitude_value New value to be copied in member altitude_value + */ +void etsi_its_cam_msgs::msg::Altitude::altitude_value( + const etsi_its_cam_msgs::msg::AltitudeValue& _altitude_value) +{ + m_altitude_value = _altitude_value; +} + +/*! + * @brief This function moves the value in member altitude_value + * @param _altitude_value New value to be moved in member altitude_value + */ +void etsi_its_cam_msgs::msg::Altitude::altitude_value( + etsi_its_cam_msgs::msg::AltitudeValue&& _altitude_value) +{ + m_altitude_value = std::move(_altitude_value); +} + +/*! + * @brief This function returns a constant reference to member altitude_value + * @return Constant reference to member altitude_value + */ +const etsi_its_cam_msgs::msg::AltitudeValue& etsi_its_cam_msgs::msg::Altitude::altitude_value() const +{ + return m_altitude_value; +} + +/*! + * @brief This function returns a reference to member altitude_value + * @return Reference to member altitude_value + */ +etsi_its_cam_msgs::msg::AltitudeValue& etsi_its_cam_msgs::msg::Altitude::altitude_value() +{ + return m_altitude_value; +} +/*! + * @brief This function copies the value in member altitude_confidence + * @param _altitude_confidence New value to be copied in member altitude_confidence + */ +void etsi_its_cam_msgs::msg::Altitude::altitude_confidence( + const etsi_its_cam_msgs::msg::AltitudeConfidence& _altitude_confidence) +{ + m_altitude_confidence = _altitude_confidence; +} + +/*! + * @brief This function moves the value in member altitude_confidence + * @param _altitude_confidence New value to be moved in member altitude_confidence + */ +void etsi_its_cam_msgs::msg::Altitude::altitude_confidence( + etsi_its_cam_msgs::msg::AltitudeConfidence&& _altitude_confidence) +{ + m_altitude_confidence = std::move(_altitude_confidence); +} + +/*! + * @brief This function returns a constant reference to member altitude_confidence + * @return Constant reference to member altitude_confidence + */ +const etsi_its_cam_msgs::msg::AltitudeConfidence& etsi_its_cam_msgs::msg::Altitude::altitude_confidence() const +{ + return m_altitude_confidence; +} + +/*! + * @brief This function returns a reference to member altitude_confidence + * @return Reference to member altitude_confidence + */ +etsi_its_cam_msgs::msg::AltitudeConfidence& etsi_its_cam_msgs::msg::Altitude::altitude_confidence() +{ + return m_altitude_confidence; +} + +size_t etsi_its_cam_msgs::msg::Altitude::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::Altitude::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::Altitude::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Altitude.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Altitude.h new file mode 100644 index 00000000000..7ca4d3a2a24 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Altitude.h @@ -0,0 +1,244 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Altitude.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDE_H_ + +#include "AltitudeConfidence.h" +#include "AltitudeValue.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(Altitude_SOURCE) +#define Altitude_DllAPI __declspec( dllexport ) +#else +#define Altitude_DllAPI __declspec( dllimport ) +#endif // Altitude_SOURCE +#else +#define Altitude_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define Altitude_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure Altitude defined by the user in the IDL file. + * @ingroup ALTITUDE + */ + class Altitude + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Altitude(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Altitude(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::Altitude that will be copied. + */ + eProsima_user_DllExport Altitude( + const Altitude& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::Altitude that will be copied. + */ + eProsima_user_DllExport Altitude( + Altitude&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::Altitude that will be copied. + */ + eProsima_user_DllExport Altitude& operator =( + const Altitude& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::Altitude that will be copied. + */ + eProsima_user_DllExport Altitude& operator =( + Altitude&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::Altitude object to compare. + */ + eProsima_user_DllExport bool operator ==( + const Altitude& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::Altitude object to compare. + */ + eProsima_user_DllExport bool operator !=( + const Altitude& x) const; + + /*! + * @brief This function copies the value in member altitude_value + * @param _altitude_value New value to be copied in member altitude_value + */ + eProsima_user_DllExport void altitude_value( + const etsi_its_cam_msgs::msg::AltitudeValue& _altitude_value); + + /*! + * @brief This function moves the value in member altitude_value + * @param _altitude_value New value to be moved in member altitude_value + */ + eProsima_user_DllExport void altitude_value( + etsi_its_cam_msgs::msg::AltitudeValue&& _altitude_value); + + /*! + * @brief This function returns a constant reference to member altitude_value + * @return Constant reference to member altitude_value + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::AltitudeValue& altitude_value() const; + + /*! + * @brief This function returns a reference to member altitude_value + * @return Reference to member altitude_value + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::AltitudeValue& altitude_value(); + /*! + * @brief This function copies the value in member altitude_confidence + * @param _altitude_confidence New value to be copied in member altitude_confidence + */ + eProsima_user_DllExport void altitude_confidence( + const etsi_its_cam_msgs::msg::AltitudeConfidence& _altitude_confidence); + + /*! + * @brief This function moves the value in member altitude_confidence + * @param _altitude_confidence New value to be moved in member altitude_confidence + */ + eProsima_user_DllExport void altitude_confidence( + etsi_its_cam_msgs::msg::AltitudeConfidence&& _altitude_confidence); + + /*! + * @brief This function returns a constant reference to member altitude_confidence + * @return Constant reference to member altitude_confidence + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::AltitudeConfidence& altitude_confidence() const; + + /*! + * @brief This function returns a reference to member altitude_confidence + * @return Reference to member altitude_confidence + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::AltitudeConfidence& altitude_confidence(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::Altitude& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::AltitudeValue m_altitude_value; + etsi_its_cam_msgs::msg::AltitudeConfidence m_altitude_confidence; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidence.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidence.cxx new file mode 100644 index 00000000000..56d8de4d586 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidence.cxx @@ -0,0 +1,200 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AltitudeConfidence.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "AltitudeConfidence.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + + + + + + + + + + + +etsi_its_cam_msgs::msg::AltitudeConfidence::AltitudeConfidence() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@540dbda9 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::AltitudeConfidence::~AltitudeConfidence() +{ +} + +etsi_its_cam_msgs::msg::AltitudeConfidence::AltitudeConfidence( + const AltitudeConfidence& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::AltitudeConfidence::AltitudeConfidence( + AltitudeConfidence&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::AltitudeConfidence& etsi_its_cam_msgs::msg::AltitudeConfidence::operator =( + const AltitudeConfidence& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::AltitudeConfidence& etsi_its_cam_msgs::msg::AltitudeConfidence::operator =( + AltitudeConfidence&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::AltitudeConfidence::operator ==( + const AltitudeConfidence& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::AltitudeConfidence::operator !=( + const AltitudeConfidence& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::AltitudeConfidence::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::AltitudeConfidence::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::AltitudeConfidence& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::AltitudeConfidence::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::AltitudeConfidence::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::AltitudeConfidence::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::AltitudeConfidence::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::AltitudeConfidence::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::AltitudeConfidence::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::AltitudeConfidence::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::AltitudeConfidence::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidence.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidence.h new file mode 100644 index 00000000000..0c35bb1ce82 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidence.h @@ -0,0 +1,228 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AltitudeConfidence.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDECONFIDENCE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDECONFIDENCE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(AltitudeConfidence_SOURCE) +#define AltitudeConfidence_DllAPI __declspec( dllexport ) +#else +#define AltitudeConfidence_DllAPI __declspec( dllimport ) +#endif // AltitudeConfidence_SOURCE +#else +#define AltitudeConfidence_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define AltitudeConfidence_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace AltitudeConfidence_Constants { + const uint8_t ALT_000_01 = 0; + const uint8_t ALT_000_02 = 1; + const uint8_t ALT_000_05 = 2; + const uint8_t ALT_000_10 = 3; + const uint8_t ALT_000_20 = 4; + const uint8_t ALT_000_50 = 5; + const uint8_t ALT_001_00 = 6; + const uint8_t ALT_002_00 = 7; + const uint8_t ALT_005_00 = 8; + const uint8_t ALT_010_00 = 9; + const uint8_t ALT_020_00 = 10; + const uint8_t ALT_050_00 = 11; + const uint8_t ALT_100_00 = 12; + const uint8_t ALT_200_00 = 13; + const uint8_t OUT_OF_RANGE = 14; + const uint8_t UNAVAILABLE = 15; + } // namespace AltitudeConfidence_Constants + /*! + * @brief This class represents the structure AltitudeConfidence defined by the user in the IDL file. + * @ingroup ALTITUDECONFIDENCE + */ + class AltitudeConfidence + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport AltitudeConfidence(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~AltitudeConfidence(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::AltitudeConfidence that will be copied. + */ + eProsima_user_DllExport AltitudeConfidence( + const AltitudeConfidence& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::AltitudeConfidence that will be copied. + */ + eProsima_user_DllExport AltitudeConfidence( + AltitudeConfidence&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::AltitudeConfidence that will be copied. + */ + eProsima_user_DllExport AltitudeConfidence& operator =( + const AltitudeConfidence& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::AltitudeConfidence that will be copied. + */ + eProsima_user_DllExport AltitudeConfidence& operator =( + AltitudeConfidence&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::AltitudeConfidence object to compare. + */ + eProsima_user_DllExport bool operator ==( + const AltitudeConfidence& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::AltitudeConfidence object to compare. + */ + eProsima_user_DllExport bool operator !=( + const AltitudeConfidence& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::AltitudeConfidence& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDECONFIDENCE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidencePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidencePubSubTypes.cxx new file mode 100644 index 00000000000..4759559641f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidencePubSubTypes.cxx @@ -0,0 +1,195 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AltitudeConfidencePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "AltitudeConfidencePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace AltitudeConfidence_Constants { + + + + + + + + + + + + + + + + + + } //End of namespace AltitudeConfidence_Constants + AltitudeConfidencePubSubType::AltitudeConfidencePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::AltitudeConfidence_"); + auto type_size = AltitudeConfidence::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = AltitudeConfidence::isKeyDefined(); + size_t keyLength = AltitudeConfidence::getKeyMaxCdrSerializedSize() > 16 ? + AltitudeConfidence::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + AltitudeConfidencePubSubType::~AltitudeConfidencePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool AltitudeConfidencePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + AltitudeConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool AltitudeConfidencePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + AltitudeConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function AltitudeConfidencePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* AltitudeConfidencePubSubType::createData() + { + return reinterpret_cast(new AltitudeConfidence()); + } + + void AltitudeConfidencePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool AltitudeConfidencePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + AltitudeConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + AltitudeConfidence::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || AltitudeConfidence::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidencePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidencePubSubTypes.h new file mode 100644 index 00000000000..c1fbf19f3b7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidencePubSubTypes.h @@ -0,0 +1,126 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AltitudeConfidencePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDECONFIDENCE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDECONFIDENCE_PUBSUBTYPES_H_ + +#include +#include + +#include "AltitudeConfidence.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated AltitudeConfidence is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace AltitudeConfidence_Constants + { + + + + + + + + + + + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type AltitudeConfidence defined by the user in the IDL file. + * @ingroup ALTITUDECONFIDENCE + */ + class AltitudeConfidencePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef AltitudeConfidence type; + + eProsima_user_DllExport AltitudeConfidencePubSubType(); + + eProsima_user_DllExport virtual ~AltitudeConfidencePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) AltitudeConfidence(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDECONFIDENCE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudePubSubTypes.cxx new file mode 100644 index 00000000000..a7a18adfcca --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudePubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AltitudePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "AltitudePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + AltitudePubSubType::AltitudePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::Altitude_"); + auto type_size = Altitude::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = Altitude::isKeyDefined(); + size_t keyLength = Altitude::getKeyMaxCdrSerializedSize() > 16 ? + Altitude::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + AltitudePubSubType::~AltitudePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool AltitudePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + Altitude* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool AltitudePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + Altitude* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function AltitudePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* AltitudePubSubType::createData() + { + return reinterpret_cast(new Altitude()); + } + + void AltitudePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool AltitudePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + Altitude* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + Altitude::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || Altitude::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudePubSubTypes.h new file mode 100644 index 00000000000..7389ed241dc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudePubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AltitudePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDE_PUBSUBTYPES_H_ + +#include +#include + +#include "Altitude.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated Altitude is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type Altitude defined by the user in the IDL file. + * @ingroup ALTITUDE + */ + class AltitudePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef Altitude type; + + eProsima_user_DllExport AltitudePubSubType(); + + eProsima_user_DllExport virtual ~AltitudePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) Altitude(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValue.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValue.cxx new file mode 100644 index 00000000000..a61347e9cfb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValue.cxx @@ -0,0 +1,189 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AltitudeValue.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "AltitudeValue.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + +etsi_its_cam_msgs::msg::AltitudeValue::AltitudeValue() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@22bd2039 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::AltitudeValue::~AltitudeValue() +{ +} + +etsi_its_cam_msgs::msg::AltitudeValue::AltitudeValue( + const AltitudeValue& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::AltitudeValue::AltitudeValue( + AltitudeValue&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::AltitudeValue& etsi_its_cam_msgs::msg::AltitudeValue::operator =( + const AltitudeValue& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::AltitudeValue& etsi_its_cam_msgs::msg::AltitudeValue::operator =( + AltitudeValue&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::AltitudeValue::operator ==( + const AltitudeValue& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::AltitudeValue::operator !=( + const AltitudeValue& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::AltitudeValue::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::AltitudeValue::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::AltitudeValue& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::AltitudeValue::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::AltitudeValue::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::AltitudeValue::value( + int32_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int32_t etsi_its_cam_msgs::msg::AltitudeValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int32_t& etsi_its_cam_msgs::msg::AltitudeValue::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::AltitudeValue::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::AltitudeValue::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::AltitudeValue::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValue.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValue.h new file mode 100644 index 00000000000..7e85c6cb2fe --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValue.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AltitudeValue.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDEVALUE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDEVALUE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(AltitudeValue_SOURCE) +#define AltitudeValue_DllAPI __declspec( dllexport ) +#else +#define AltitudeValue_DllAPI __declspec( dllimport ) +#endif // AltitudeValue_SOURCE +#else +#define AltitudeValue_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define AltitudeValue_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace AltitudeValue_Constants { + const int32_t MIN = -100000; + const int32_t MAX = 800001; + const int32_t REFERENCE_ELLIPSOID_SURFACE = 0; + const int32_t ONE_CENTIMETER = 1; + const int32_t UNAVAILABLE = 800001; + } // namespace AltitudeValue_Constants + /*! + * @brief This class represents the structure AltitudeValue defined by the user in the IDL file. + * @ingroup ALTITUDEVALUE + */ + class AltitudeValue + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport AltitudeValue(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~AltitudeValue(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::AltitudeValue that will be copied. + */ + eProsima_user_DllExport AltitudeValue( + const AltitudeValue& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::AltitudeValue that will be copied. + */ + eProsima_user_DllExport AltitudeValue( + AltitudeValue&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::AltitudeValue that will be copied. + */ + eProsima_user_DllExport AltitudeValue& operator =( + const AltitudeValue& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::AltitudeValue that will be copied. + */ + eProsima_user_DllExport AltitudeValue& operator =( + AltitudeValue&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::AltitudeValue object to compare. + */ + eProsima_user_DllExport bool operator ==( + const AltitudeValue& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::AltitudeValue object to compare. + */ + eProsima_user_DllExport bool operator !=( + const AltitudeValue& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + int32_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport int32_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport int32_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::AltitudeValue& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + int32_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDEVALUE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValuePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValuePubSubTypes.cxx new file mode 100644 index 00000000000..2757a77d662 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValuePubSubTypes.cxx @@ -0,0 +1,184 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AltitudeValuePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "AltitudeValuePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace AltitudeValue_Constants { + + + + + + + } //End of namespace AltitudeValue_Constants + AltitudeValuePubSubType::AltitudeValuePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::AltitudeValue_"); + auto type_size = AltitudeValue::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = AltitudeValue::isKeyDefined(); + size_t keyLength = AltitudeValue::getKeyMaxCdrSerializedSize() > 16 ? + AltitudeValue::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + AltitudeValuePubSubType::~AltitudeValuePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool AltitudeValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + AltitudeValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool AltitudeValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + AltitudeValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function AltitudeValuePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* AltitudeValuePubSubType::createData() + { + return reinterpret_cast(new AltitudeValue()); + } + + void AltitudeValuePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool AltitudeValuePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + AltitudeValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + AltitudeValue::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || AltitudeValue::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValuePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValuePubSubTypes.h new file mode 100644 index 00000000000..d347db612ac --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValuePubSubTypes.h @@ -0,0 +1,115 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AltitudeValuePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDEVALUE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDEVALUE_PUBSUBTYPES_H_ + +#include +#include + +#include "AltitudeValue.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated AltitudeValue is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace AltitudeValue_Constants + { + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type AltitudeValue defined by the user in the IDL file. + * @ingroup ALTITUDEVALUE + */ + class AltitudeValuePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef AltitudeValue type; + + eProsima_user_DllExport AltitudeValuePubSubType(); + + eProsima_user_DllExport virtual ~AltitudeValuePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) AltitudeValue(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDEVALUE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainer.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainer.cxx new file mode 100644 index 00000000000..50f3dbfe26d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainer.cxx @@ -0,0 +1,238 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file BasicContainer.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "BasicContainer.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::BasicContainer::BasicContainer() +{ + // m_station_type com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@432034a + + // m_reference_position com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@78de58ea + + +} + +etsi_its_cam_msgs::msg::BasicContainer::~BasicContainer() +{ + +} + +etsi_its_cam_msgs::msg::BasicContainer::BasicContainer( + const BasicContainer& x) +{ + m_station_type = x.m_station_type; + m_reference_position = x.m_reference_position; +} + +etsi_its_cam_msgs::msg::BasicContainer::BasicContainer( + BasicContainer&& x) +{ + m_station_type = std::move(x.m_station_type); + m_reference_position = std::move(x.m_reference_position); +} + +etsi_its_cam_msgs::msg::BasicContainer& etsi_its_cam_msgs::msg::BasicContainer::operator =( + const BasicContainer& x) +{ + + m_station_type = x.m_station_type; + m_reference_position = x.m_reference_position; + + return *this; +} + +etsi_its_cam_msgs::msg::BasicContainer& etsi_its_cam_msgs::msg::BasicContainer::operator =( + BasicContainer&& x) +{ + + m_station_type = std::move(x.m_station_type); + m_reference_position = std::move(x.m_reference_position); + + return *this; +} + +bool etsi_its_cam_msgs::msg::BasicContainer::operator ==( + const BasicContainer& x) const +{ + + return (m_station_type == x.m_station_type && m_reference_position == x.m_reference_position); +} + +bool etsi_its_cam_msgs::msg::BasicContainer::operator !=( + const BasicContainer& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::BasicContainer::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::StationType::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::ReferencePosition::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::BasicContainer::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::BasicContainer& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::StationType::getCdrSerializedSize(data.station_type(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::ReferencePosition::getCdrSerializedSize(data.reference_position(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::BasicContainer::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_station_type; + scdr << m_reference_position; + +} + +void etsi_its_cam_msgs::msg::BasicContainer::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_station_type; + dcdr >> m_reference_position; +} + +/*! + * @brief This function copies the value in member station_type + * @param _station_type New value to be copied in member station_type + */ +void etsi_its_cam_msgs::msg::BasicContainer::station_type( + const etsi_its_cam_msgs::msg::StationType& _station_type) +{ + m_station_type = _station_type; +} + +/*! + * @brief This function moves the value in member station_type + * @param _station_type New value to be moved in member station_type + */ +void etsi_its_cam_msgs::msg::BasicContainer::station_type( + etsi_its_cam_msgs::msg::StationType&& _station_type) +{ + m_station_type = std::move(_station_type); +} + +/*! + * @brief This function returns a constant reference to member station_type + * @return Constant reference to member station_type + */ +const etsi_its_cam_msgs::msg::StationType& etsi_its_cam_msgs::msg::BasicContainer::station_type() const +{ + return m_station_type; +} + +/*! + * @brief This function returns a reference to member station_type + * @return Reference to member station_type + */ +etsi_its_cam_msgs::msg::StationType& etsi_its_cam_msgs::msg::BasicContainer::station_type() +{ + return m_station_type; +} +/*! + * @brief This function copies the value in member reference_position + * @param _reference_position New value to be copied in member reference_position + */ +void etsi_its_cam_msgs::msg::BasicContainer::reference_position( + const etsi_its_cam_msgs::msg::ReferencePosition& _reference_position) +{ + m_reference_position = _reference_position; +} + +/*! + * @brief This function moves the value in member reference_position + * @param _reference_position New value to be moved in member reference_position + */ +void etsi_its_cam_msgs::msg::BasicContainer::reference_position( + etsi_its_cam_msgs::msg::ReferencePosition&& _reference_position) +{ + m_reference_position = std::move(_reference_position); +} + +/*! + * @brief This function returns a constant reference to member reference_position + * @return Constant reference to member reference_position + */ +const etsi_its_cam_msgs::msg::ReferencePosition& etsi_its_cam_msgs::msg::BasicContainer::reference_position() const +{ + return m_reference_position; +} + +/*! + * @brief This function returns a reference to member reference_position + * @return Reference to member reference_position + */ +etsi_its_cam_msgs::msg::ReferencePosition& etsi_its_cam_msgs::msg::BasicContainer::reference_position() +{ + return m_reference_position; +} + +size_t etsi_its_cam_msgs::msg::BasicContainer::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::BasicContainer::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::BasicContainer::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainer.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainer.h new file mode 100644 index 00000000000..632ceafad36 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainer.h @@ -0,0 +1,244 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file BasicContainer.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICCONTAINER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICCONTAINER_H_ + +#include "ReferencePosition.h" +#include "StationType.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(BasicContainer_SOURCE) +#define BasicContainer_DllAPI __declspec( dllexport ) +#else +#define BasicContainer_DllAPI __declspec( dllimport ) +#endif // BasicContainer_SOURCE +#else +#define BasicContainer_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define BasicContainer_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure BasicContainer defined by the user in the IDL file. + * @ingroup BASICCONTAINER + */ + class BasicContainer + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport BasicContainer(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~BasicContainer(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::BasicContainer that will be copied. + */ + eProsima_user_DllExport BasicContainer( + const BasicContainer& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::BasicContainer that will be copied. + */ + eProsima_user_DllExport BasicContainer( + BasicContainer&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::BasicContainer that will be copied. + */ + eProsima_user_DllExport BasicContainer& operator =( + const BasicContainer& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::BasicContainer that will be copied. + */ + eProsima_user_DllExport BasicContainer& operator =( + BasicContainer&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::BasicContainer object to compare. + */ + eProsima_user_DllExport bool operator ==( + const BasicContainer& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::BasicContainer object to compare. + */ + eProsima_user_DllExport bool operator !=( + const BasicContainer& x) const; + + /*! + * @brief This function copies the value in member station_type + * @param _station_type New value to be copied in member station_type + */ + eProsima_user_DllExport void station_type( + const etsi_its_cam_msgs::msg::StationType& _station_type); + + /*! + * @brief This function moves the value in member station_type + * @param _station_type New value to be moved in member station_type + */ + eProsima_user_DllExport void station_type( + etsi_its_cam_msgs::msg::StationType&& _station_type); + + /*! + * @brief This function returns a constant reference to member station_type + * @return Constant reference to member station_type + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::StationType& station_type() const; + + /*! + * @brief This function returns a reference to member station_type + * @return Reference to member station_type + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::StationType& station_type(); + /*! + * @brief This function copies the value in member reference_position + * @param _reference_position New value to be copied in member reference_position + */ + eProsima_user_DllExport void reference_position( + const etsi_its_cam_msgs::msg::ReferencePosition& _reference_position); + + /*! + * @brief This function moves the value in member reference_position + * @param _reference_position New value to be moved in member reference_position + */ + eProsima_user_DllExport void reference_position( + etsi_its_cam_msgs::msg::ReferencePosition&& _reference_position); + + /*! + * @brief This function returns a constant reference to member reference_position + * @return Constant reference to member reference_position + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::ReferencePosition& reference_position() const; + + /*! + * @brief This function returns a reference to member reference_position + * @return Reference to member reference_position + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::ReferencePosition& reference_position(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::BasicContainer& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::StationType m_station_type; + etsi_its_cam_msgs::msg::ReferencePosition m_reference_position; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICCONTAINER_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainerPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainerPubSubTypes.cxx new file mode 100644 index 00000000000..16e86f50ad3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainerPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file BasicContainerPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "BasicContainerPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + BasicContainerPubSubType::BasicContainerPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::BasicContainer_"); + auto type_size = BasicContainer::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = BasicContainer::isKeyDefined(); + size_t keyLength = BasicContainer::getKeyMaxCdrSerializedSize() > 16 ? + BasicContainer::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + BasicContainerPubSubType::~BasicContainerPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool BasicContainerPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + BasicContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool BasicContainerPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + BasicContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function BasicContainerPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* BasicContainerPubSubType::createData() + { + return reinterpret_cast(new BasicContainer()); + } + + void BasicContainerPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool BasicContainerPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + BasicContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + BasicContainer::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || BasicContainer::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainerPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainerPubSubTypes.h new file mode 100644 index 00000000000..22c59616956 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainerPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file BasicContainerPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICCONTAINER_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICCONTAINER_PUBSUBTYPES_H_ + +#include +#include + +#include "BasicContainer.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated BasicContainer is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type BasicContainer defined by the user in the IDL file. + * @ingroup BASICCONTAINER + */ + class BasicContainerPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef BasicContainer type; + + eProsima_user_DllExport BasicContainerPubSubType(); + + eProsima_user_DllExport virtual ~BasicContainerPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) BasicContainer(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICCONTAINER_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.cxx new file mode 100644 index 00000000000..c954bbbbf21 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.cxx @@ -0,0 +1,1211 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file BasicVehicleContainerHighFrequency.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "BasicVehicleContainerHighFrequency.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::BasicVehicleContainerHighFrequency() +{ + // m_heading com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@5aa6202e + + // m_speed com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@3af9aa66 + + // m_drive_direction com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@771158fb + + // m_vehicle_length com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@91c4a3f + + // m_vehicle_width com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@62d0ac62 + + // m_longitudinal_acceleration com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@150d80c4 + + // m_curvature com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@6826c41e + + // m_curvature_calculation_mode com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@3003697 + + // m_yaw_rate com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@64d43929 + + // m_acceleration_control com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@1d269ed7 + + // m_acceleration_control_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@437ebf59 + m_acceleration_control_is_present = false; + // m_lane_position com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@41c89d2f + + // m_lane_position_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@410e94e + m_lane_position_is_present = false; + // m_steering_wheel_angle com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@2d691f3d + + // m_steering_wheel_angle_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@1bdbf9be + m_steering_wheel_angle_is_present = false; + // m_lateral_acceleration com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@1e7f2e0f + + // m_lateral_acceleration_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@1da6ee17 + m_lateral_acceleration_is_present = false; + // m_vertical_acceleration com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@78d39a69 + + // m_vertical_acceleration_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@3c818ac4 + m_vertical_acceleration_is_present = false; + // m_performance_class com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@5b69d40d + + // m_performance_class_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@71154f21 + m_performance_class_is_present = false; + // m_cen_dsrc_tolling_zone com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@15f193b8 + + // m_cen_dsrc_tolling_zone_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@2516fc68 + m_cen_dsrc_tolling_zone_is_present = false; + +} + +etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::~BasicVehicleContainerHighFrequency() +{ + + + + + + + + + + + + + + + + + + + + + + +} + +etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::BasicVehicleContainerHighFrequency( + const BasicVehicleContainerHighFrequency& x) +{ + m_heading = x.m_heading; + m_speed = x.m_speed; + m_drive_direction = x.m_drive_direction; + m_vehicle_length = x.m_vehicle_length; + m_vehicle_width = x.m_vehicle_width; + m_longitudinal_acceleration = x.m_longitudinal_acceleration; + m_curvature = x.m_curvature; + m_curvature_calculation_mode = x.m_curvature_calculation_mode; + m_yaw_rate = x.m_yaw_rate; + m_acceleration_control = x.m_acceleration_control; + m_acceleration_control_is_present = x.m_acceleration_control_is_present; + m_lane_position = x.m_lane_position; + m_lane_position_is_present = x.m_lane_position_is_present; + m_steering_wheel_angle = x.m_steering_wheel_angle; + m_steering_wheel_angle_is_present = x.m_steering_wheel_angle_is_present; + m_lateral_acceleration = x.m_lateral_acceleration; + m_lateral_acceleration_is_present = x.m_lateral_acceleration_is_present; + m_vertical_acceleration = x.m_vertical_acceleration; + m_vertical_acceleration_is_present = x.m_vertical_acceleration_is_present; + m_performance_class = x.m_performance_class; + m_performance_class_is_present = x.m_performance_class_is_present; + m_cen_dsrc_tolling_zone = x.m_cen_dsrc_tolling_zone; + m_cen_dsrc_tolling_zone_is_present = x.m_cen_dsrc_tolling_zone_is_present; +} + +etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::BasicVehicleContainerHighFrequency( + BasicVehicleContainerHighFrequency&& x) +{ + m_heading = std::move(x.m_heading); + m_speed = std::move(x.m_speed); + m_drive_direction = std::move(x.m_drive_direction); + m_vehicle_length = std::move(x.m_vehicle_length); + m_vehicle_width = std::move(x.m_vehicle_width); + m_longitudinal_acceleration = std::move(x.m_longitudinal_acceleration); + m_curvature = std::move(x.m_curvature); + m_curvature_calculation_mode = std::move(x.m_curvature_calculation_mode); + m_yaw_rate = std::move(x.m_yaw_rate); + m_acceleration_control = std::move(x.m_acceleration_control); + m_acceleration_control_is_present = x.m_acceleration_control_is_present; + m_lane_position = std::move(x.m_lane_position); + m_lane_position_is_present = x.m_lane_position_is_present; + m_steering_wheel_angle = std::move(x.m_steering_wheel_angle); + m_steering_wheel_angle_is_present = x.m_steering_wheel_angle_is_present; + m_lateral_acceleration = std::move(x.m_lateral_acceleration); + m_lateral_acceleration_is_present = x.m_lateral_acceleration_is_present; + m_vertical_acceleration = std::move(x.m_vertical_acceleration); + m_vertical_acceleration_is_present = x.m_vertical_acceleration_is_present; + m_performance_class = std::move(x.m_performance_class); + m_performance_class_is_present = x.m_performance_class_is_present; + m_cen_dsrc_tolling_zone = std::move(x.m_cen_dsrc_tolling_zone); + m_cen_dsrc_tolling_zone_is_present = x.m_cen_dsrc_tolling_zone_is_present; +} + +etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::operator =( + const BasicVehicleContainerHighFrequency& x) +{ + + m_heading = x.m_heading; + m_speed = x.m_speed; + m_drive_direction = x.m_drive_direction; + m_vehicle_length = x.m_vehicle_length; + m_vehicle_width = x.m_vehicle_width; + m_longitudinal_acceleration = x.m_longitudinal_acceleration; + m_curvature = x.m_curvature; + m_curvature_calculation_mode = x.m_curvature_calculation_mode; + m_yaw_rate = x.m_yaw_rate; + m_acceleration_control = x.m_acceleration_control; + m_acceleration_control_is_present = x.m_acceleration_control_is_present; + m_lane_position = x.m_lane_position; + m_lane_position_is_present = x.m_lane_position_is_present; + m_steering_wheel_angle = x.m_steering_wheel_angle; + m_steering_wheel_angle_is_present = x.m_steering_wheel_angle_is_present; + m_lateral_acceleration = x.m_lateral_acceleration; + m_lateral_acceleration_is_present = x.m_lateral_acceleration_is_present; + m_vertical_acceleration = x.m_vertical_acceleration; + m_vertical_acceleration_is_present = x.m_vertical_acceleration_is_present; + m_performance_class = x.m_performance_class; + m_performance_class_is_present = x.m_performance_class_is_present; + m_cen_dsrc_tolling_zone = x.m_cen_dsrc_tolling_zone; + m_cen_dsrc_tolling_zone_is_present = x.m_cen_dsrc_tolling_zone_is_present; + + return *this; +} + +etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::operator =( + BasicVehicleContainerHighFrequency&& x) +{ + + m_heading = std::move(x.m_heading); + m_speed = std::move(x.m_speed); + m_drive_direction = std::move(x.m_drive_direction); + m_vehicle_length = std::move(x.m_vehicle_length); + m_vehicle_width = std::move(x.m_vehicle_width); + m_longitudinal_acceleration = std::move(x.m_longitudinal_acceleration); + m_curvature = std::move(x.m_curvature); + m_curvature_calculation_mode = std::move(x.m_curvature_calculation_mode); + m_yaw_rate = std::move(x.m_yaw_rate); + m_acceleration_control = std::move(x.m_acceleration_control); + m_acceleration_control_is_present = x.m_acceleration_control_is_present; + m_lane_position = std::move(x.m_lane_position); + m_lane_position_is_present = x.m_lane_position_is_present; + m_steering_wheel_angle = std::move(x.m_steering_wheel_angle); + m_steering_wheel_angle_is_present = x.m_steering_wheel_angle_is_present; + m_lateral_acceleration = std::move(x.m_lateral_acceleration); + m_lateral_acceleration_is_present = x.m_lateral_acceleration_is_present; + m_vertical_acceleration = std::move(x.m_vertical_acceleration); + m_vertical_acceleration_is_present = x.m_vertical_acceleration_is_present; + m_performance_class = std::move(x.m_performance_class); + m_performance_class_is_present = x.m_performance_class_is_present; + m_cen_dsrc_tolling_zone = std::move(x.m_cen_dsrc_tolling_zone); + m_cen_dsrc_tolling_zone_is_present = x.m_cen_dsrc_tolling_zone_is_present; + + return *this; +} + +bool etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::operator ==( + const BasicVehicleContainerHighFrequency& x) const +{ + + return (m_heading == x.m_heading && m_speed == x.m_speed && m_drive_direction == x.m_drive_direction && m_vehicle_length == x.m_vehicle_length && m_vehicle_width == x.m_vehicle_width && m_longitudinal_acceleration == x.m_longitudinal_acceleration && m_curvature == x.m_curvature && m_curvature_calculation_mode == x.m_curvature_calculation_mode && m_yaw_rate == x.m_yaw_rate && m_acceleration_control == x.m_acceleration_control && m_acceleration_control_is_present == x.m_acceleration_control_is_present && m_lane_position == x.m_lane_position && m_lane_position_is_present == x.m_lane_position_is_present && m_steering_wheel_angle == x.m_steering_wheel_angle && m_steering_wheel_angle_is_present == x.m_steering_wheel_angle_is_present && m_lateral_acceleration == x.m_lateral_acceleration && m_lateral_acceleration_is_present == x.m_lateral_acceleration_is_present && m_vertical_acceleration == x.m_vertical_acceleration && m_vertical_acceleration_is_present == x.m_vertical_acceleration_is_present && m_performance_class == x.m_performance_class && m_performance_class_is_present == x.m_performance_class_is_present && m_cen_dsrc_tolling_zone == x.m_cen_dsrc_tolling_zone && m_cen_dsrc_tolling_zone_is_present == x.m_cen_dsrc_tolling_zone_is_present); +} + +bool etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::operator !=( + const BasicVehicleContainerHighFrequency& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::Heading::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::Speed::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::DriveDirection::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::VehicleLength::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::VehicleWidth::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::LongitudinalAcceleration::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::Curvature::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::CurvatureCalculationMode::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::YawRate::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::AccelerationControl::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::LanePosition::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::SteeringWheelAngle::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::LateralAcceleration::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::VerticalAcceleration::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::PerformanceClass::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::CenDsrcTollingZone::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::Heading::getCdrSerializedSize(data.heading(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::Speed::getCdrSerializedSize(data.speed(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::DriveDirection::getCdrSerializedSize(data.drive_direction(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::VehicleLength::getCdrSerializedSize(data.vehicle_length(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::VehicleWidth::getCdrSerializedSize(data.vehicle_width(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::LongitudinalAcceleration::getCdrSerializedSize(data.longitudinal_acceleration(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::Curvature::getCdrSerializedSize(data.curvature(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::CurvatureCalculationMode::getCdrSerializedSize(data.curvature_calculation_mode(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::YawRate::getCdrSerializedSize(data.yaw_rate(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::AccelerationControl::getCdrSerializedSize(data.acceleration_control(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::LanePosition::getCdrSerializedSize(data.lane_position(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::SteeringWheelAngle::getCdrSerializedSize(data.steering_wheel_angle(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::LateralAcceleration::getCdrSerializedSize(data.lateral_acceleration(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::VerticalAcceleration::getCdrSerializedSize(data.vertical_acceleration(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::PerformanceClass::getCdrSerializedSize(data.performance_class(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::CenDsrcTollingZone::getCdrSerializedSize(data.cen_dsrc_tolling_zone(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_heading; + scdr << m_speed; + scdr << m_drive_direction; + scdr << m_vehicle_length; + scdr << m_vehicle_width; + scdr << m_longitudinal_acceleration; + scdr << m_curvature; + scdr << m_curvature_calculation_mode; + scdr << m_yaw_rate; + scdr << m_acceleration_control; + scdr << m_acceleration_control_is_present; + scdr << m_lane_position; + scdr << m_lane_position_is_present; + scdr << m_steering_wheel_angle; + scdr << m_steering_wheel_angle_is_present; + scdr << m_lateral_acceleration; + scdr << m_lateral_acceleration_is_present; + scdr << m_vertical_acceleration; + scdr << m_vertical_acceleration_is_present; + scdr << m_performance_class; + scdr << m_performance_class_is_present; + scdr << m_cen_dsrc_tolling_zone; + scdr << m_cen_dsrc_tolling_zone_is_present; + +} + +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_heading; + dcdr >> m_speed; + dcdr >> m_drive_direction; + dcdr >> m_vehicle_length; + dcdr >> m_vehicle_width; + dcdr >> m_longitudinal_acceleration; + dcdr >> m_curvature; + dcdr >> m_curvature_calculation_mode; + dcdr >> m_yaw_rate; + dcdr >> m_acceleration_control; + dcdr >> m_acceleration_control_is_present; + dcdr >> m_lane_position; + dcdr >> m_lane_position_is_present; + dcdr >> m_steering_wheel_angle; + dcdr >> m_steering_wheel_angle_is_present; + dcdr >> m_lateral_acceleration; + dcdr >> m_lateral_acceleration_is_present; + dcdr >> m_vertical_acceleration; + dcdr >> m_vertical_acceleration_is_present; + dcdr >> m_performance_class; + dcdr >> m_performance_class_is_present; + dcdr >> m_cen_dsrc_tolling_zone; + dcdr >> m_cen_dsrc_tolling_zone_is_present; +} + +/*! + * @brief This function copies the value in member heading_ + * @param _heading New value to be copied in member heading_ + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::heading( + const etsi_its_cam_msgs::msg::Heading& _heading) +{ + m_heading = _heading; +} + +/*! + * @brief This function moves the value in member heading_ + * @param _heading New value to be moved in member heading_ + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::heading( + etsi_its_cam_msgs::msg::Heading&& _heading) +{ + m_heading = std::move(_heading); +} + +/*! + * @brief This function returns a constant reference to member heading_ + * @return Constant reference to member heading_ + */ +const etsi_its_cam_msgs::msg::Heading& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::heading() const +{ + return m_heading; +} + +/*! + * @brief This function returns a reference to member heading_ + * @return Reference to member heading_ + */ +etsi_its_cam_msgs::msg::Heading& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::heading() +{ + return m_heading; +} +/*! + * @brief This function copies the value in member speed_ + * @param _speed New value to be copied in member speed_ + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::speed( + const etsi_its_cam_msgs::msg::Speed& _speed) +{ + m_speed = _speed; +} + +/*! + * @brief This function moves the value in member speed_ + * @param _speed New value to be moved in member speed_ + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::speed( + etsi_its_cam_msgs::msg::Speed&& _speed) +{ + m_speed = std::move(_speed); +} + +/*! + * @brief This function returns a constant reference to member speed_ + * @return Constant reference to member speed_ + */ +const etsi_its_cam_msgs::msg::Speed& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::speed() const +{ + return m_speed; +} + +/*! + * @brief This function returns a reference to member speed_ + * @return Reference to member speed_ + */ +etsi_its_cam_msgs::msg::Speed& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::speed() +{ + return m_speed; +} +/*! + * @brief This function copies the value in member drive_direction + * @param _drive_direction New value to be copied in member drive_direction + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::drive_direction( + const etsi_its_cam_msgs::msg::DriveDirection& _drive_direction) +{ + m_drive_direction = _drive_direction; +} + +/*! + * @brief This function moves the value in member drive_direction + * @param _drive_direction New value to be moved in member drive_direction + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::drive_direction( + etsi_its_cam_msgs::msg::DriveDirection&& _drive_direction) +{ + m_drive_direction = std::move(_drive_direction); +} + +/*! + * @brief This function returns a constant reference to member drive_direction + * @return Constant reference to member drive_direction + */ +const etsi_its_cam_msgs::msg::DriveDirection& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::drive_direction() const +{ + return m_drive_direction; +} + +/*! + * @brief This function returns a reference to member drive_direction + * @return Reference to member drive_direction + */ +etsi_its_cam_msgs::msg::DriveDirection& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::drive_direction() +{ + return m_drive_direction; +} +/*! + * @brief This function copies the value in member vehicle_length + * @param _vehicle_length New value to be copied in member vehicle_length + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::vehicle_length( + const etsi_its_cam_msgs::msg::VehicleLength& _vehicle_length) +{ + m_vehicle_length = _vehicle_length; +} + +/*! + * @brief This function moves the value in member vehicle_length + * @param _vehicle_length New value to be moved in member vehicle_length + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::vehicle_length( + etsi_its_cam_msgs::msg::VehicleLength&& _vehicle_length) +{ + m_vehicle_length = std::move(_vehicle_length); +} + +/*! + * @brief This function returns a constant reference to member vehicle_length + * @return Constant reference to member vehicle_length + */ +const etsi_its_cam_msgs::msg::VehicleLength& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::vehicle_length() const +{ + return m_vehicle_length; +} + +/*! + * @brief This function returns a reference to member vehicle_length + * @return Reference to member vehicle_length + */ +etsi_its_cam_msgs::msg::VehicleLength& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::vehicle_length() +{ + return m_vehicle_length; +} +/*! + * @brief This function copies the value in member vehicle_width + * @param _vehicle_width New value to be copied in member vehicle_width + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::vehicle_width( + const etsi_its_cam_msgs::msg::VehicleWidth& _vehicle_width) +{ + m_vehicle_width = _vehicle_width; +} + +/*! + * @brief This function moves the value in member vehicle_width + * @param _vehicle_width New value to be moved in member vehicle_width + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::vehicle_width( + etsi_its_cam_msgs::msg::VehicleWidth&& _vehicle_width) +{ + m_vehicle_width = std::move(_vehicle_width); +} + +/*! + * @brief This function returns a constant reference to member vehicle_width + * @return Constant reference to member vehicle_width + */ +const etsi_its_cam_msgs::msg::VehicleWidth& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::vehicle_width() const +{ + return m_vehicle_width; +} + +/*! + * @brief This function returns a reference to member vehicle_width + * @return Reference to member vehicle_width + */ +etsi_its_cam_msgs::msg::VehicleWidth& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::vehicle_width() +{ + return m_vehicle_width; +} +/*! + * @brief This function copies the value in member longitudinal_acceleration + * @param _longitudinal_acceleration New value to be copied in member longitudinal_acceleration + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::longitudinal_acceleration( + const etsi_its_cam_msgs::msg::LongitudinalAcceleration& _longitudinal_acceleration) +{ + m_longitudinal_acceleration = _longitudinal_acceleration; +} + +/*! + * @brief This function moves the value in member longitudinal_acceleration + * @param _longitudinal_acceleration New value to be moved in member longitudinal_acceleration + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::longitudinal_acceleration( + etsi_its_cam_msgs::msg::LongitudinalAcceleration&& _longitudinal_acceleration) +{ + m_longitudinal_acceleration = std::move(_longitudinal_acceleration); +} + +/*! + * @brief This function returns a constant reference to member longitudinal_acceleration + * @return Constant reference to member longitudinal_acceleration + */ +const etsi_its_cam_msgs::msg::LongitudinalAcceleration& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::longitudinal_acceleration() const +{ + return m_longitudinal_acceleration; +} + +/*! + * @brief This function returns a reference to member longitudinal_acceleration + * @return Reference to member longitudinal_acceleration + */ +etsi_its_cam_msgs::msg::LongitudinalAcceleration& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::longitudinal_acceleration() +{ + return m_longitudinal_acceleration; +} +/*! + * @brief This function copies the value in member curvature_ + * @param _curvature New value to be copied in member curvature_ + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::curvature( + const etsi_its_cam_msgs::msg::Curvature& _curvature) +{ + m_curvature = _curvature; +} + +/*! + * @brief This function moves the value in member curvature_ + * @param _curvature New value to be moved in member curvature_ + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::curvature( + etsi_its_cam_msgs::msg::Curvature&& _curvature) +{ + m_curvature = std::move(_curvature); +} + +/*! + * @brief This function returns a constant reference to member curvature_ + * @return Constant reference to member curvature_ + */ +const etsi_its_cam_msgs::msg::Curvature& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::curvature() const +{ + return m_curvature; +} + +/*! + * @brief This function returns a reference to member curvature_ + * @return Reference to member curvature_ + */ +etsi_its_cam_msgs::msg::Curvature& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::curvature() +{ + return m_curvature; +} +/*! + * @brief This function copies the value in member curvature_calculation_mode + * @param _curvature_calculation_mode New value to be copied in member curvature_calculation_mode + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::curvature_calculation_mode( + const etsi_its_cam_msgs::msg::CurvatureCalculationMode& _curvature_calculation_mode) +{ + m_curvature_calculation_mode = _curvature_calculation_mode; +} + +/*! + * @brief This function moves the value in member curvature_calculation_mode + * @param _curvature_calculation_mode New value to be moved in member curvature_calculation_mode + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::curvature_calculation_mode( + etsi_its_cam_msgs::msg::CurvatureCalculationMode&& _curvature_calculation_mode) +{ + m_curvature_calculation_mode = std::move(_curvature_calculation_mode); +} + +/*! + * @brief This function returns a constant reference to member curvature_calculation_mode + * @return Constant reference to member curvature_calculation_mode + */ +const etsi_its_cam_msgs::msg::CurvatureCalculationMode& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::curvature_calculation_mode() const +{ + return m_curvature_calculation_mode; +} + +/*! + * @brief This function returns a reference to member curvature_calculation_mode + * @return Reference to member curvature_calculation_mode + */ +etsi_its_cam_msgs::msg::CurvatureCalculationMode& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::curvature_calculation_mode() +{ + return m_curvature_calculation_mode; +} +/*! + * @brief This function copies the value in member yaw_rate + * @param _yaw_rate New value to be copied in member yaw_rate + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::yaw_rate( + const etsi_its_cam_msgs::msg::YawRate& _yaw_rate) +{ + m_yaw_rate = _yaw_rate; +} + +/*! + * @brief This function moves the value in member yaw_rate + * @param _yaw_rate New value to be moved in member yaw_rate + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::yaw_rate( + etsi_its_cam_msgs::msg::YawRate&& _yaw_rate) +{ + m_yaw_rate = std::move(_yaw_rate); +} + +/*! + * @brief This function returns a constant reference to member yaw_rate + * @return Constant reference to member yaw_rate + */ +const etsi_its_cam_msgs::msg::YawRate& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::yaw_rate() const +{ + return m_yaw_rate; +} + +/*! + * @brief This function returns a reference to member yaw_rate + * @return Reference to member yaw_rate + */ +etsi_its_cam_msgs::msg::YawRate& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::yaw_rate() +{ + return m_yaw_rate; +} +/*! + * @brief This function copies the value in member acceleration_control + * @param _acceleration_control New value to be copied in member acceleration_control + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::acceleration_control( + const etsi_its_cam_msgs::msg::AccelerationControl& _acceleration_control) +{ + m_acceleration_control = _acceleration_control; +} + +/*! + * @brief This function moves the value in member acceleration_control + * @param _acceleration_control New value to be moved in member acceleration_control + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::acceleration_control( + etsi_its_cam_msgs::msg::AccelerationControl&& _acceleration_control) +{ + m_acceleration_control = std::move(_acceleration_control); +} + +/*! + * @brief This function returns a constant reference to member acceleration_control + * @return Constant reference to member acceleration_control + */ +const etsi_its_cam_msgs::msg::AccelerationControl& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::acceleration_control() const +{ + return m_acceleration_control; +} + +/*! + * @brief This function returns a reference to member acceleration_control + * @return Reference to member acceleration_control + */ +etsi_its_cam_msgs::msg::AccelerationControl& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::acceleration_control() +{ + return m_acceleration_control; +} +/*! + * @brief This function sets a value in member acceleration_control_is_present + * @param _acceleration_control_is_present New value for member acceleration_control_is_present + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::acceleration_control_is_present( + bool _acceleration_control_is_present) +{ + m_acceleration_control_is_present = _acceleration_control_is_present; +} + +/*! + * @brief This function returns the value of member acceleration_control_is_present + * @return Value of member acceleration_control_is_present + */ +bool etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::acceleration_control_is_present() const +{ + return m_acceleration_control_is_present; +} + +/*! + * @brief This function returns a reference to member acceleration_control_is_present + * @return Reference to member acceleration_control_is_present + */ +bool& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::acceleration_control_is_present() +{ + return m_acceleration_control_is_present; +} + +/*! + * @brief This function copies the value in member lane_position + * @param _lane_position New value to be copied in member lane_position + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::lane_position( + const etsi_its_cam_msgs::msg::LanePosition& _lane_position) +{ + m_lane_position = _lane_position; +} + +/*! + * @brief This function moves the value in member lane_position + * @param _lane_position New value to be moved in member lane_position + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::lane_position( + etsi_its_cam_msgs::msg::LanePosition&& _lane_position) +{ + m_lane_position = std::move(_lane_position); +} + +/*! + * @brief This function returns a constant reference to member lane_position + * @return Constant reference to member lane_position + */ +const etsi_its_cam_msgs::msg::LanePosition& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::lane_position() const +{ + return m_lane_position; +} + +/*! + * @brief This function returns a reference to member lane_position + * @return Reference to member lane_position + */ +etsi_its_cam_msgs::msg::LanePosition& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::lane_position() +{ + return m_lane_position; +} +/*! + * @brief This function sets a value in member lane_position_is_present + * @param _lane_position_is_present New value for member lane_position_is_present + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::lane_position_is_present( + bool _lane_position_is_present) +{ + m_lane_position_is_present = _lane_position_is_present; +} + +/*! + * @brief This function returns the value of member lane_position_is_present + * @return Value of member lane_position_is_present + */ +bool etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::lane_position_is_present() const +{ + return m_lane_position_is_present; +} + +/*! + * @brief This function returns a reference to member lane_position_is_present + * @return Reference to member lane_position_is_present + */ +bool& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::lane_position_is_present() +{ + return m_lane_position_is_present; +} + +/*! + * @brief This function copies the value in member steering_wheel_angle + * @param _steering_wheel_angle New value to be copied in member steering_wheel_angle + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::steering_wheel_angle( + const etsi_its_cam_msgs::msg::SteeringWheelAngle& _steering_wheel_angle) +{ + m_steering_wheel_angle = _steering_wheel_angle; +} + +/*! + * @brief This function moves the value in member steering_wheel_angle + * @param _steering_wheel_angle New value to be moved in member steering_wheel_angle + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::steering_wheel_angle( + etsi_its_cam_msgs::msg::SteeringWheelAngle&& _steering_wheel_angle) +{ + m_steering_wheel_angle = std::move(_steering_wheel_angle); +} + +/*! + * @brief This function returns a constant reference to member steering_wheel_angle + * @return Constant reference to member steering_wheel_angle + */ +const etsi_its_cam_msgs::msg::SteeringWheelAngle& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::steering_wheel_angle() const +{ + return m_steering_wheel_angle; +} + +/*! + * @brief This function returns a reference to member steering_wheel_angle + * @return Reference to member steering_wheel_angle + */ +etsi_its_cam_msgs::msg::SteeringWheelAngle& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::steering_wheel_angle() +{ + return m_steering_wheel_angle; +} +/*! + * @brief This function sets a value in member steering_wheel_angle_is_present + * @param _steering_wheel_angle_is_present New value for member steering_wheel_angle_is_present + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::steering_wheel_angle_is_present( + bool _steering_wheel_angle_is_present) +{ + m_steering_wheel_angle_is_present = _steering_wheel_angle_is_present; +} + +/*! + * @brief This function returns the value of member steering_wheel_angle_is_present + * @return Value of member steering_wheel_angle_is_present + */ +bool etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::steering_wheel_angle_is_present() const +{ + return m_steering_wheel_angle_is_present; +} + +/*! + * @brief This function returns a reference to member steering_wheel_angle_is_present + * @return Reference to member steering_wheel_angle_is_present + */ +bool& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::steering_wheel_angle_is_present() +{ + return m_steering_wheel_angle_is_present; +} + +/*! + * @brief This function copies the value in member lateral_acceleration + * @param _lateral_acceleration New value to be copied in member lateral_acceleration + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::lateral_acceleration( + const etsi_its_cam_msgs::msg::LateralAcceleration& _lateral_acceleration) +{ + m_lateral_acceleration = _lateral_acceleration; +} + +/*! + * @brief This function moves the value in member lateral_acceleration + * @param _lateral_acceleration New value to be moved in member lateral_acceleration + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::lateral_acceleration( + etsi_its_cam_msgs::msg::LateralAcceleration&& _lateral_acceleration) +{ + m_lateral_acceleration = std::move(_lateral_acceleration); +} + +/*! + * @brief This function returns a constant reference to member lateral_acceleration + * @return Constant reference to member lateral_acceleration + */ +const etsi_its_cam_msgs::msg::LateralAcceleration& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::lateral_acceleration() const +{ + return m_lateral_acceleration; +} + +/*! + * @brief This function returns a reference to member lateral_acceleration + * @return Reference to member lateral_acceleration + */ +etsi_its_cam_msgs::msg::LateralAcceleration& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::lateral_acceleration() +{ + return m_lateral_acceleration; +} +/*! + * @brief This function sets a value in member lateral_acceleration_is_present + * @param _lateral_acceleration_is_present New value for member lateral_acceleration_is_present + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::lateral_acceleration_is_present( + bool _lateral_acceleration_is_present) +{ + m_lateral_acceleration_is_present = _lateral_acceleration_is_present; +} + +/*! + * @brief This function returns the value of member lateral_acceleration_is_present + * @return Value of member lateral_acceleration_is_present + */ +bool etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::lateral_acceleration_is_present() const +{ + return m_lateral_acceleration_is_present; +} + +/*! + * @brief This function returns a reference to member lateral_acceleration_is_present + * @return Reference to member lateral_acceleration_is_present + */ +bool& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::lateral_acceleration_is_present() +{ + return m_lateral_acceleration_is_present; +} + +/*! + * @brief This function copies the value in member vertical_acceleration + * @param _vertical_acceleration New value to be copied in member vertical_acceleration + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::vertical_acceleration( + const etsi_its_cam_msgs::msg::VerticalAcceleration& _vertical_acceleration) +{ + m_vertical_acceleration = _vertical_acceleration; +} + +/*! + * @brief This function moves the value in member vertical_acceleration + * @param _vertical_acceleration New value to be moved in member vertical_acceleration + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::vertical_acceleration( + etsi_its_cam_msgs::msg::VerticalAcceleration&& _vertical_acceleration) +{ + m_vertical_acceleration = std::move(_vertical_acceleration); +} + +/*! + * @brief This function returns a constant reference to member vertical_acceleration + * @return Constant reference to member vertical_acceleration + */ +const etsi_its_cam_msgs::msg::VerticalAcceleration& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::vertical_acceleration() const +{ + return m_vertical_acceleration; +} + +/*! + * @brief This function returns a reference to member vertical_acceleration + * @return Reference to member vertical_acceleration + */ +etsi_its_cam_msgs::msg::VerticalAcceleration& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::vertical_acceleration() +{ + return m_vertical_acceleration; +} +/*! + * @brief This function sets a value in member vertical_acceleration_is_present + * @param _vertical_acceleration_is_present New value for member vertical_acceleration_is_present + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::vertical_acceleration_is_present( + bool _vertical_acceleration_is_present) +{ + m_vertical_acceleration_is_present = _vertical_acceleration_is_present; +} + +/*! + * @brief This function returns the value of member vertical_acceleration_is_present + * @return Value of member vertical_acceleration_is_present + */ +bool etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::vertical_acceleration_is_present() const +{ + return m_vertical_acceleration_is_present; +} + +/*! + * @brief This function returns a reference to member vertical_acceleration_is_present + * @return Reference to member vertical_acceleration_is_present + */ +bool& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::vertical_acceleration_is_present() +{ + return m_vertical_acceleration_is_present; +} + +/*! + * @brief This function copies the value in member performance_class + * @param _performance_class New value to be copied in member performance_class + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::performance_class( + const etsi_its_cam_msgs::msg::PerformanceClass& _performance_class) +{ + m_performance_class = _performance_class; +} + +/*! + * @brief This function moves the value in member performance_class + * @param _performance_class New value to be moved in member performance_class + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::performance_class( + etsi_its_cam_msgs::msg::PerformanceClass&& _performance_class) +{ + m_performance_class = std::move(_performance_class); +} + +/*! + * @brief This function returns a constant reference to member performance_class + * @return Constant reference to member performance_class + */ +const etsi_its_cam_msgs::msg::PerformanceClass& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::performance_class() const +{ + return m_performance_class; +} + +/*! + * @brief This function returns a reference to member performance_class + * @return Reference to member performance_class + */ +etsi_its_cam_msgs::msg::PerformanceClass& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::performance_class() +{ + return m_performance_class; +} +/*! + * @brief This function sets a value in member performance_class_is_present + * @param _performance_class_is_present New value for member performance_class_is_present + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::performance_class_is_present( + bool _performance_class_is_present) +{ + m_performance_class_is_present = _performance_class_is_present; +} + +/*! + * @brief This function returns the value of member performance_class_is_present + * @return Value of member performance_class_is_present + */ +bool etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::performance_class_is_present() const +{ + return m_performance_class_is_present; +} + +/*! + * @brief This function returns a reference to member performance_class_is_present + * @return Reference to member performance_class_is_present + */ +bool& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::performance_class_is_present() +{ + return m_performance_class_is_present; +} + +/*! + * @brief This function copies the value in member cen_dsrc_tolling_zone + * @param _cen_dsrc_tolling_zone New value to be copied in member cen_dsrc_tolling_zone + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::cen_dsrc_tolling_zone( + const etsi_its_cam_msgs::msg::CenDsrcTollingZone& _cen_dsrc_tolling_zone) +{ + m_cen_dsrc_tolling_zone = _cen_dsrc_tolling_zone; +} + +/*! + * @brief This function moves the value in member cen_dsrc_tolling_zone + * @param _cen_dsrc_tolling_zone New value to be moved in member cen_dsrc_tolling_zone + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::cen_dsrc_tolling_zone( + etsi_its_cam_msgs::msg::CenDsrcTollingZone&& _cen_dsrc_tolling_zone) +{ + m_cen_dsrc_tolling_zone = std::move(_cen_dsrc_tolling_zone); +} + +/*! + * @brief This function returns a constant reference to member cen_dsrc_tolling_zone + * @return Constant reference to member cen_dsrc_tolling_zone + */ +const etsi_its_cam_msgs::msg::CenDsrcTollingZone& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::cen_dsrc_tolling_zone() const +{ + return m_cen_dsrc_tolling_zone; +} + +/*! + * @brief This function returns a reference to member cen_dsrc_tolling_zone + * @return Reference to member cen_dsrc_tolling_zone + */ +etsi_its_cam_msgs::msg::CenDsrcTollingZone& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::cen_dsrc_tolling_zone() +{ + return m_cen_dsrc_tolling_zone; +} +/*! + * @brief This function sets a value in member cen_dsrc_tolling_zone_is_present + * @param _cen_dsrc_tolling_zone_is_present New value for member cen_dsrc_tolling_zone_is_present + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::cen_dsrc_tolling_zone_is_present( + bool _cen_dsrc_tolling_zone_is_present) +{ + m_cen_dsrc_tolling_zone_is_present = _cen_dsrc_tolling_zone_is_present; +} + +/*! + * @brief This function returns the value of member cen_dsrc_tolling_zone_is_present + * @return Value of member cen_dsrc_tolling_zone_is_present + */ +bool etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::cen_dsrc_tolling_zone_is_present() const +{ + return m_cen_dsrc_tolling_zone_is_present; +} + +/*! + * @brief This function returns a reference to member cen_dsrc_tolling_zone_is_present + * @return Reference to member cen_dsrc_tolling_zone_is_present + */ +bool& etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::cen_dsrc_tolling_zone_is_present() +{ + return m_cen_dsrc_tolling_zone_is_present; +} + + +size_t etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.h new file mode 100644 index 00000000000..2ebb6a5f341 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.h @@ -0,0 +1,762 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file BasicVehicleContainerHighFrequency.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERHIGHFREQUENCY_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERHIGHFREQUENCY_H_ + +#include "DriveDirection.h" +#include "Speed.h" +#include "Heading.h" +#include "VehicleWidth.h" +#include "CenDsrcTollingZone.h" +#include "YawRate.h" +#include "VehicleLength.h" +#include "CurvatureCalculationMode.h" +#include "LanePosition.h" +#include "LateralAcceleration.h" +#include "VerticalAcceleration.h" +#include "SteeringWheelAngle.h" +#include "LongitudinalAcceleration.h" +#include "Curvature.h" +#include "PerformanceClass.h" +#include "AccelerationControl.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(BasicVehicleContainerHighFrequency_SOURCE) +#define BasicVehicleContainerHighFrequency_DllAPI __declspec( dllexport ) +#else +#define BasicVehicleContainerHighFrequency_DllAPI __declspec( dllimport ) +#endif // BasicVehicleContainerHighFrequency_SOURCE +#else +#define BasicVehicleContainerHighFrequency_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define BasicVehicleContainerHighFrequency_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure BasicVehicleContainerHighFrequency defined by the user in the IDL file. + * @ingroup BASICVEHICLECONTAINERHIGHFREQUENCY + */ + class BasicVehicleContainerHighFrequency + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport BasicVehicleContainerHighFrequency(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~BasicVehicleContainerHighFrequency(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency that will be copied. + */ + eProsima_user_DllExport BasicVehicleContainerHighFrequency( + const BasicVehicleContainerHighFrequency& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency that will be copied. + */ + eProsima_user_DllExport BasicVehicleContainerHighFrequency( + BasicVehicleContainerHighFrequency&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency that will be copied. + */ + eProsima_user_DllExport BasicVehicleContainerHighFrequency& operator =( + const BasicVehicleContainerHighFrequency& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency that will be copied. + */ + eProsima_user_DllExport BasicVehicleContainerHighFrequency& operator =( + BasicVehicleContainerHighFrequency&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency object to compare. + */ + eProsima_user_DllExport bool operator ==( + const BasicVehicleContainerHighFrequency& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency object to compare. + */ + eProsima_user_DllExport bool operator !=( + const BasicVehicleContainerHighFrequency& x) const; + + /*! + * @brief This function copies the value in member heading_ + * @param _heading New value to be copied in member heading_ + */ + eProsima_user_DllExport void heading( + const etsi_its_cam_msgs::msg::Heading& _heading); + + /*! + * @brief This function moves the value in member heading_ + * @param _heading New value to be moved in member heading_ + */ + eProsima_user_DllExport void heading( + etsi_its_cam_msgs::msg::Heading&& _heading); + + /*! + * @brief This function returns a constant reference to member heading_ + * @return Constant reference to member heading_ + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::Heading& heading() const; + + /*! + * @brief This function returns a reference to member heading_ + * @return Reference to member heading_ + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::Heading& heading(); + /*! + * @brief This function copies the value in member speed_ + * @param _speed New value to be copied in member speed_ + */ + eProsima_user_DllExport void speed( + const etsi_its_cam_msgs::msg::Speed& _speed); + + /*! + * @brief This function moves the value in member speed_ + * @param _speed New value to be moved in member speed_ + */ + eProsima_user_DllExport void speed( + etsi_its_cam_msgs::msg::Speed&& _speed); + + /*! + * @brief This function returns a constant reference to member speed_ + * @return Constant reference to member speed_ + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::Speed& speed() const; + + /*! + * @brief This function returns a reference to member speed_ + * @return Reference to member speed_ + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::Speed& speed(); + /*! + * @brief This function copies the value in member drive_direction + * @param _drive_direction New value to be copied in member drive_direction + */ + eProsima_user_DllExport void drive_direction( + const etsi_its_cam_msgs::msg::DriveDirection& _drive_direction); + + /*! + * @brief This function moves the value in member drive_direction + * @param _drive_direction New value to be moved in member drive_direction + */ + eProsima_user_DllExport void drive_direction( + etsi_its_cam_msgs::msg::DriveDirection&& _drive_direction); + + /*! + * @brief This function returns a constant reference to member drive_direction + * @return Constant reference to member drive_direction + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::DriveDirection& drive_direction() const; + + /*! + * @brief This function returns a reference to member drive_direction + * @return Reference to member drive_direction + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::DriveDirection& drive_direction(); + /*! + * @brief This function copies the value in member vehicle_length + * @param _vehicle_length New value to be copied in member vehicle_length + */ + eProsima_user_DllExport void vehicle_length( + const etsi_its_cam_msgs::msg::VehicleLength& _vehicle_length); + + /*! + * @brief This function moves the value in member vehicle_length + * @param _vehicle_length New value to be moved in member vehicle_length + */ + eProsima_user_DllExport void vehicle_length( + etsi_its_cam_msgs::msg::VehicleLength&& _vehicle_length); + + /*! + * @brief This function returns a constant reference to member vehicle_length + * @return Constant reference to member vehicle_length + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::VehicleLength& vehicle_length() const; + + /*! + * @brief This function returns a reference to member vehicle_length + * @return Reference to member vehicle_length + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::VehicleLength& vehicle_length(); + /*! + * @brief This function copies the value in member vehicle_width + * @param _vehicle_width New value to be copied in member vehicle_width + */ + eProsima_user_DllExport void vehicle_width( + const etsi_its_cam_msgs::msg::VehicleWidth& _vehicle_width); + + /*! + * @brief This function moves the value in member vehicle_width + * @param _vehicle_width New value to be moved in member vehicle_width + */ + eProsima_user_DllExport void vehicle_width( + etsi_its_cam_msgs::msg::VehicleWidth&& _vehicle_width); + + /*! + * @brief This function returns a constant reference to member vehicle_width + * @return Constant reference to member vehicle_width + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::VehicleWidth& vehicle_width() const; + + /*! + * @brief This function returns a reference to member vehicle_width + * @return Reference to member vehicle_width + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::VehicleWidth& vehicle_width(); + /*! + * @brief This function copies the value in member longitudinal_acceleration + * @param _longitudinal_acceleration New value to be copied in member longitudinal_acceleration + */ + eProsima_user_DllExport void longitudinal_acceleration( + const etsi_its_cam_msgs::msg::LongitudinalAcceleration& _longitudinal_acceleration); + + /*! + * @brief This function moves the value in member longitudinal_acceleration + * @param _longitudinal_acceleration New value to be moved in member longitudinal_acceleration + */ + eProsima_user_DllExport void longitudinal_acceleration( + etsi_its_cam_msgs::msg::LongitudinalAcceleration&& _longitudinal_acceleration); + + /*! + * @brief This function returns a constant reference to member longitudinal_acceleration + * @return Constant reference to member longitudinal_acceleration + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::LongitudinalAcceleration& longitudinal_acceleration() const; + + /*! + * @brief This function returns a reference to member longitudinal_acceleration + * @return Reference to member longitudinal_acceleration + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::LongitudinalAcceleration& longitudinal_acceleration(); + /*! + * @brief This function copies the value in member curvature_ + * @param _curvature New value to be copied in member curvature_ + */ + eProsima_user_DllExport void curvature( + const etsi_its_cam_msgs::msg::Curvature& _curvature); + + /*! + * @brief This function moves the value in member curvature_ + * @param _curvature New value to be moved in member curvature_ + */ + eProsima_user_DllExport void curvature( + etsi_its_cam_msgs::msg::Curvature&& _curvature); + + /*! + * @brief This function returns a constant reference to member curvature_ + * @return Constant reference to member curvature_ + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::Curvature& curvature() const; + + /*! + * @brief This function returns a reference to member curvature_ + * @return Reference to member curvature_ + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::Curvature& curvature(); + /*! + * @brief This function copies the value in member curvature_calculation_mode + * @param _curvature_calculation_mode New value to be copied in member curvature_calculation_mode + */ + eProsima_user_DllExport void curvature_calculation_mode( + const etsi_its_cam_msgs::msg::CurvatureCalculationMode& _curvature_calculation_mode); + + /*! + * @brief This function moves the value in member curvature_calculation_mode + * @param _curvature_calculation_mode New value to be moved in member curvature_calculation_mode + */ + eProsima_user_DllExport void curvature_calculation_mode( + etsi_its_cam_msgs::msg::CurvatureCalculationMode&& _curvature_calculation_mode); + + /*! + * @brief This function returns a constant reference to member curvature_calculation_mode + * @return Constant reference to member curvature_calculation_mode + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::CurvatureCalculationMode& curvature_calculation_mode() const; + + /*! + * @brief This function returns a reference to member curvature_calculation_mode + * @return Reference to member curvature_calculation_mode + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::CurvatureCalculationMode& curvature_calculation_mode(); + /*! + * @brief This function copies the value in member yaw_rate + * @param _yaw_rate New value to be copied in member yaw_rate + */ + eProsima_user_DllExport void yaw_rate( + const etsi_its_cam_msgs::msg::YawRate& _yaw_rate); + + /*! + * @brief This function moves the value in member yaw_rate + * @param _yaw_rate New value to be moved in member yaw_rate + */ + eProsima_user_DllExport void yaw_rate( + etsi_its_cam_msgs::msg::YawRate&& _yaw_rate); + + /*! + * @brief This function returns a constant reference to member yaw_rate + * @return Constant reference to member yaw_rate + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::YawRate& yaw_rate() const; + + /*! + * @brief This function returns a reference to member yaw_rate + * @return Reference to member yaw_rate + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::YawRate& yaw_rate(); + /*! + * @brief This function copies the value in member acceleration_control + * @param _acceleration_control New value to be copied in member acceleration_control + */ + eProsima_user_DllExport void acceleration_control( + const etsi_its_cam_msgs::msg::AccelerationControl& _acceleration_control); + + /*! + * @brief This function moves the value in member acceleration_control + * @param _acceleration_control New value to be moved in member acceleration_control + */ + eProsima_user_DllExport void acceleration_control( + etsi_its_cam_msgs::msg::AccelerationControl&& _acceleration_control); + + /*! + * @brief This function returns a constant reference to member acceleration_control + * @return Constant reference to member acceleration_control + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::AccelerationControl& acceleration_control() const; + + /*! + * @brief This function returns a reference to member acceleration_control + * @return Reference to member acceleration_control + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::AccelerationControl& acceleration_control(); + /*! + * @brief This function sets a value in member acceleration_control_is_present + * @param _acceleration_control_is_present New value for member acceleration_control_is_present + */ + eProsima_user_DllExport void acceleration_control_is_present( + bool _acceleration_control_is_present); + + /*! + * @brief This function returns the value of member acceleration_control_is_present + * @return Value of member acceleration_control_is_present + */ + eProsima_user_DllExport bool acceleration_control_is_present() const; + + /*! + * @brief This function returns a reference to member acceleration_control_is_present + * @return Reference to member acceleration_control_is_present + */ + eProsima_user_DllExport bool& acceleration_control_is_present(); + + /*! + * @brief This function copies the value in member lane_position + * @param _lane_position New value to be copied in member lane_position + */ + eProsima_user_DllExport void lane_position( + const etsi_its_cam_msgs::msg::LanePosition& _lane_position); + + /*! + * @brief This function moves the value in member lane_position + * @param _lane_position New value to be moved in member lane_position + */ + eProsima_user_DllExport void lane_position( + etsi_its_cam_msgs::msg::LanePosition&& _lane_position); + + /*! + * @brief This function returns a constant reference to member lane_position + * @return Constant reference to member lane_position + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::LanePosition& lane_position() const; + + /*! + * @brief This function returns a reference to member lane_position + * @return Reference to member lane_position + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::LanePosition& lane_position(); + /*! + * @brief This function sets a value in member lane_position_is_present + * @param _lane_position_is_present New value for member lane_position_is_present + */ + eProsima_user_DllExport void lane_position_is_present( + bool _lane_position_is_present); + + /*! + * @brief This function returns the value of member lane_position_is_present + * @return Value of member lane_position_is_present + */ + eProsima_user_DllExport bool lane_position_is_present() const; + + /*! + * @brief This function returns a reference to member lane_position_is_present + * @return Reference to member lane_position_is_present + */ + eProsima_user_DllExport bool& lane_position_is_present(); + + /*! + * @brief This function copies the value in member steering_wheel_angle + * @param _steering_wheel_angle New value to be copied in member steering_wheel_angle + */ + eProsima_user_DllExport void steering_wheel_angle( + const etsi_its_cam_msgs::msg::SteeringWheelAngle& _steering_wheel_angle); + + /*! + * @brief This function moves the value in member steering_wheel_angle + * @param _steering_wheel_angle New value to be moved in member steering_wheel_angle + */ + eProsima_user_DllExport void steering_wheel_angle( + etsi_its_cam_msgs::msg::SteeringWheelAngle&& _steering_wheel_angle); + + /*! + * @brief This function returns a constant reference to member steering_wheel_angle + * @return Constant reference to member steering_wheel_angle + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::SteeringWheelAngle& steering_wheel_angle() const; + + /*! + * @brief This function returns a reference to member steering_wheel_angle + * @return Reference to member steering_wheel_angle + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::SteeringWheelAngle& steering_wheel_angle(); + /*! + * @brief This function sets a value in member steering_wheel_angle_is_present + * @param _steering_wheel_angle_is_present New value for member steering_wheel_angle_is_present + */ + eProsima_user_DllExport void steering_wheel_angle_is_present( + bool _steering_wheel_angle_is_present); + + /*! + * @brief This function returns the value of member steering_wheel_angle_is_present + * @return Value of member steering_wheel_angle_is_present + */ + eProsima_user_DllExport bool steering_wheel_angle_is_present() const; + + /*! + * @brief This function returns a reference to member steering_wheel_angle_is_present + * @return Reference to member steering_wheel_angle_is_present + */ + eProsima_user_DllExport bool& steering_wheel_angle_is_present(); + + /*! + * @brief This function copies the value in member lateral_acceleration + * @param _lateral_acceleration New value to be copied in member lateral_acceleration + */ + eProsima_user_DllExport void lateral_acceleration( + const etsi_its_cam_msgs::msg::LateralAcceleration& _lateral_acceleration); + + /*! + * @brief This function moves the value in member lateral_acceleration + * @param _lateral_acceleration New value to be moved in member lateral_acceleration + */ + eProsima_user_DllExport void lateral_acceleration( + etsi_its_cam_msgs::msg::LateralAcceleration&& _lateral_acceleration); + + /*! + * @brief This function returns a constant reference to member lateral_acceleration + * @return Constant reference to member lateral_acceleration + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::LateralAcceleration& lateral_acceleration() const; + + /*! + * @brief This function returns a reference to member lateral_acceleration + * @return Reference to member lateral_acceleration + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::LateralAcceleration& lateral_acceleration(); + /*! + * @brief This function sets a value in member lateral_acceleration_is_present + * @param _lateral_acceleration_is_present New value for member lateral_acceleration_is_present + */ + eProsima_user_DllExport void lateral_acceleration_is_present( + bool _lateral_acceleration_is_present); + + /*! + * @brief This function returns the value of member lateral_acceleration_is_present + * @return Value of member lateral_acceleration_is_present + */ + eProsima_user_DllExport bool lateral_acceleration_is_present() const; + + /*! + * @brief This function returns a reference to member lateral_acceleration_is_present + * @return Reference to member lateral_acceleration_is_present + */ + eProsima_user_DllExport bool& lateral_acceleration_is_present(); + + /*! + * @brief This function copies the value in member vertical_acceleration + * @param _vertical_acceleration New value to be copied in member vertical_acceleration + */ + eProsima_user_DllExport void vertical_acceleration( + const etsi_its_cam_msgs::msg::VerticalAcceleration& _vertical_acceleration); + + /*! + * @brief This function moves the value in member vertical_acceleration + * @param _vertical_acceleration New value to be moved in member vertical_acceleration + */ + eProsima_user_DllExport void vertical_acceleration( + etsi_its_cam_msgs::msg::VerticalAcceleration&& _vertical_acceleration); + + /*! + * @brief This function returns a constant reference to member vertical_acceleration + * @return Constant reference to member vertical_acceleration + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::VerticalAcceleration& vertical_acceleration() const; + + /*! + * @brief This function returns a reference to member vertical_acceleration + * @return Reference to member vertical_acceleration + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::VerticalAcceleration& vertical_acceleration(); + /*! + * @brief This function sets a value in member vertical_acceleration_is_present + * @param _vertical_acceleration_is_present New value for member vertical_acceleration_is_present + */ + eProsima_user_DllExport void vertical_acceleration_is_present( + bool _vertical_acceleration_is_present); + + /*! + * @brief This function returns the value of member vertical_acceleration_is_present + * @return Value of member vertical_acceleration_is_present + */ + eProsima_user_DllExport bool vertical_acceleration_is_present() const; + + /*! + * @brief This function returns a reference to member vertical_acceleration_is_present + * @return Reference to member vertical_acceleration_is_present + */ + eProsima_user_DllExport bool& vertical_acceleration_is_present(); + + /*! + * @brief This function copies the value in member performance_class + * @param _performance_class New value to be copied in member performance_class + */ + eProsima_user_DllExport void performance_class( + const etsi_its_cam_msgs::msg::PerformanceClass& _performance_class); + + /*! + * @brief This function moves the value in member performance_class + * @param _performance_class New value to be moved in member performance_class + */ + eProsima_user_DllExport void performance_class( + etsi_its_cam_msgs::msg::PerformanceClass&& _performance_class); + + /*! + * @brief This function returns a constant reference to member performance_class + * @return Constant reference to member performance_class + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::PerformanceClass& performance_class() const; + + /*! + * @brief This function returns a reference to member performance_class + * @return Reference to member performance_class + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::PerformanceClass& performance_class(); + /*! + * @brief This function sets a value in member performance_class_is_present + * @param _performance_class_is_present New value for member performance_class_is_present + */ + eProsima_user_DllExport void performance_class_is_present( + bool _performance_class_is_present); + + /*! + * @brief This function returns the value of member performance_class_is_present + * @return Value of member performance_class_is_present + */ + eProsima_user_DllExport bool performance_class_is_present() const; + + /*! + * @brief This function returns a reference to member performance_class_is_present + * @return Reference to member performance_class_is_present + */ + eProsima_user_DllExport bool& performance_class_is_present(); + + /*! + * @brief This function copies the value in member cen_dsrc_tolling_zone + * @param _cen_dsrc_tolling_zone New value to be copied in member cen_dsrc_tolling_zone + */ + eProsima_user_DllExport void cen_dsrc_tolling_zone( + const etsi_its_cam_msgs::msg::CenDsrcTollingZone& _cen_dsrc_tolling_zone); + + /*! + * @brief This function moves the value in member cen_dsrc_tolling_zone + * @param _cen_dsrc_tolling_zone New value to be moved in member cen_dsrc_tolling_zone + */ + eProsima_user_DllExport void cen_dsrc_tolling_zone( + etsi_its_cam_msgs::msg::CenDsrcTollingZone&& _cen_dsrc_tolling_zone); + + /*! + * @brief This function returns a constant reference to member cen_dsrc_tolling_zone + * @return Constant reference to member cen_dsrc_tolling_zone + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::CenDsrcTollingZone& cen_dsrc_tolling_zone() const; + + /*! + * @brief This function returns a reference to member cen_dsrc_tolling_zone + * @return Reference to member cen_dsrc_tolling_zone + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::CenDsrcTollingZone& cen_dsrc_tolling_zone(); + /*! + * @brief This function sets a value in member cen_dsrc_tolling_zone_is_present + * @param _cen_dsrc_tolling_zone_is_present New value for member cen_dsrc_tolling_zone_is_present + */ + eProsima_user_DllExport void cen_dsrc_tolling_zone_is_present( + bool _cen_dsrc_tolling_zone_is_present); + + /*! + * @brief This function returns the value of member cen_dsrc_tolling_zone_is_present + * @return Value of member cen_dsrc_tolling_zone_is_present + */ + eProsima_user_DllExport bool cen_dsrc_tolling_zone_is_present() const; + + /*! + * @brief This function returns a reference to member cen_dsrc_tolling_zone_is_present + * @return Reference to member cen_dsrc_tolling_zone_is_present + */ + eProsima_user_DllExport bool& cen_dsrc_tolling_zone_is_present(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::Heading m_heading; + etsi_its_cam_msgs::msg::Speed m_speed; + etsi_its_cam_msgs::msg::DriveDirection m_drive_direction; + etsi_its_cam_msgs::msg::VehicleLength m_vehicle_length; + etsi_its_cam_msgs::msg::VehicleWidth m_vehicle_width; + etsi_its_cam_msgs::msg::LongitudinalAcceleration m_longitudinal_acceleration; + etsi_its_cam_msgs::msg::Curvature m_curvature; + etsi_its_cam_msgs::msg::CurvatureCalculationMode m_curvature_calculation_mode; + etsi_its_cam_msgs::msg::YawRate m_yaw_rate; + etsi_its_cam_msgs::msg::AccelerationControl m_acceleration_control; + bool m_acceleration_control_is_present; + etsi_its_cam_msgs::msg::LanePosition m_lane_position; + bool m_lane_position_is_present; + etsi_its_cam_msgs::msg::SteeringWheelAngle m_steering_wheel_angle; + bool m_steering_wheel_angle_is_present; + etsi_its_cam_msgs::msg::LateralAcceleration m_lateral_acceleration; + bool m_lateral_acceleration_is_present; + etsi_its_cam_msgs::msg::VerticalAcceleration m_vertical_acceleration; + bool m_vertical_acceleration_is_present; + etsi_its_cam_msgs::msg::PerformanceClass m_performance_class; + bool m_performance_class_is_present; + etsi_its_cam_msgs::msg::CenDsrcTollingZone m_cen_dsrc_tolling_zone; + bool m_cen_dsrc_tolling_zone_is_present; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERHIGHFREQUENCY_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequencyPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequencyPubSubTypes.cxx new file mode 100644 index 00000000000..9a127480329 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequencyPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file BasicVehicleContainerHighFrequencyPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "BasicVehicleContainerHighFrequencyPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + BasicVehicleContainerHighFrequencyPubSubType::BasicVehicleContainerHighFrequencyPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::BasicVehicleContainerHighFrequency_"); + auto type_size = BasicVehicleContainerHighFrequency::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = BasicVehicleContainerHighFrequency::isKeyDefined(); + size_t keyLength = BasicVehicleContainerHighFrequency::getKeyMaxCdrSerializedSize() > 16 ? + BasicVehicleContainerHighFrequency::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + BasicVehicleContainerHighFrequencyPubSubType::~BasicVehicleContainerHighFrequencyPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool BasicVehicleContainerHighFrequencyPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + BasicVehicleContainerHighFrequency* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool BasicVehicleContainerHighFrequencyPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + BasicVehicleContainerHighFrequency* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function BasicVehicleContainerHighFrequencyPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* BasicVehicleContainerHighFrequencyPubSubType::createData() + { + return reinterpret_cast(new BasicVehicleContainerHighFrequency()); + } + + void BasicVehicleContainerHighFrequencyPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool BasicVehicleContainerHighFrequencyPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + BasicVehicleContainerHighFrequency* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + BasicVehicleContainerHighFrequency::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || BasicVehicleContainerHighFrequency::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequencyPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequencyPubSubTypes.h new file mode 100644 index 00000000000..963ba23024e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequencyPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file BasicVehicleContainerHighFrequencyPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERHIGHFREQUENCY_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERHIGHFREQUENCY_PUBSUBTYPES_H_ + +#include +#include + +#include "BasicVehicleContainerHighFrequency.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated BasicVehicleContainerHighFrequency is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type BasicVehicleContainerHighFrequency defined by the user in the IDL file. + * @ingroup BASICVEHICLECONTAINERHIGHFREQUENCY + */ + class BasicVehicleContainerHighFrequencyPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef BasicVehicleContainerHighFrequency type; + + eProsima_user_DllExport BasicVehicleContainerHighFrequencyPubSubType(); + + eProsima_user_DllExport virtual ~BasicVehicleContainerHighFrequencyPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERHIGHFREQUENCY_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.cxx new file mode 100644 index 00000000000..6123b6a7f4e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.cxx @@ -0,0 +1,286 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file BasicVehicleContainerLowFrequency.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "BasicVehicleContainerLowFrequency.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::BasicVehicleContainerLowFrequency() +{ + // m_vehicle_role com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@210386e0 + + // m_exterior_lights com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@3d4d3fe7 + + // m_path_history com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@65f87a2c + + +} + +etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::~BasicVehicleContainerLowFrequency() +{ + + +} + +etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::BasicVehicleContainerLowFrequency( + const BasicVehicleContainerLowFrequency& x) +{ + m_vehicle_role = x.m_vehicle_role; + m_exterior_lights = x.m_exterior_lights; + m_path_history = x.m_path_history; +} + +etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::BasicVehicleContainerLowFrequency( + BasicVehicleContainerLowFrequency&& x) +{ + m_vehicle_role = std::move(x.m_vehicle_role); + m_exterior_lights = std::move(x.m_exterior_lights); + m_path_history = std::move(x.m_path_history); +} + +etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency& etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::operator =( + const BasicVehicleContainerLowFrequency& x) +{ + + m_vehicle_role = x.m_vehicle_role; + m_exterior_lights = x.m_exterior_lights; + m_path_history = x.m_path_history; + + return *this; +} + +etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency& etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::operator =( + BasicVehicleContainerLowFrequency&& x) +{ + + m_vehicle_role = std::move(x.m_vehicle_role); + m_exterior_lights = std::move(x.m_exterior_lights); + m_path_history = std::move(x.m_path_history); + + return *this; +} + +bool etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::operator ==( + const BasicVehicleContainerLowFrequency& x) const +{ + + return (m_vehicle_role == x.m_vehicle_role && m_exterior_lights == x.m_exterior_lights && m_path_history == x.m_path_history); +} + +bool etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::operator !=( + const BasicVehicleContainerLowFrequency& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::VehicleRole::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::ExteriorLights::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::PathHistory::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::VehicleRole::getCdrSerializedSize(data.vehicle_role(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::ExteriorLights::getCdrSerializedSize(data.exterior_lights(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::PathHistory::getCdrSerializedSize(data.path_history(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_vehicle_role; + scdr << m_exterior_lights; + scdr << m_path_history; + +} + +void etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_vehicle_role; + dcdr >> m_exterior_lights; + dcdr >> m_path_history; +} + +/*! + * @brief This function copies the value in member vehicle_role + * @param _vehicle_role New value to be copied in member vehicle_role + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::vehicle_role( + const etsi_its_cam_msgs::msg::VehicleRole& _vehicle_role) +{ + m_vehicle_role = _vehicle_role; +} + +/*! + * @brief This function moves the value in member vehicle_role + * @param _vehicle_role New value to be moved in member vehicle_role + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::vehicle_role( + etsi_its_cam_msgs::msg::VehicleRole&& _vehicle_role) +{ + m_vehicle_role = std::move(_vehicle_role); +} + +/*! + * @brief This function returns a constant reference to member vehicle_role + * @return Constant reference to member vehicle_role + */ +const etsi_its_cam_msgs::msg::VehicleRole& etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::vehicle_role() const +{ + return m_vehicle_role; +} + +/*! + * @brief This function returns a reference to member vehicle_role + * @return Reference to member vehicle_role + */ +etsi_its_cam_msgs::msg::VehicleRole& etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::vehicle_role() +{ + return m_vehicle_role; +} +/*! + * @brief This function copies the value in member exterior_lights + * @param _exterior_lights New value to be copied in member exterior_lights + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::exterior_lights( + const etsi_its_cam_msgs::msg::ExteriorLights& _exterior_lights) +{ + m_exterior_lights = _exterior_lights; +} + +/*! + * @brief This function moves the value in member exterior_lights + * @param _exterior_lights New value to be moved in member exterior_lights + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::exterior_lights( + etsi_its_cam_msgs::msg::ExteriorLights&& _exterior_lights) +{ + m_exterior_lights = std::move(_exterior_lights); +} + +/*! + * @brief This function returns a constant reference to member exterior_lights + * @return Constant reference to member exterior_lights + */ +const etsi_its_cam_msgs::msg::ExteriorLights& etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::exterior_lights() const +{ + return m_exterior_lights; +} + +/*! + * @brief This function returns a reference to member exterior_lights + * @return Reference to member exterior_lights + */ +etsi_its_cam_msgs::msg::ExteriorLights& etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::exterior_lights() +{ + return m_exterior_lights; +} +/*! + * @brief This function copies the value in member path_history + * @param _path_history New value to be copied in member path_history + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::path_history( + const etsi_its_cam_msgs::msg::PathHistory& _path_history) +{ + m_path_history = _path_history; +} + +/*! + * @brief This function moves the value in member path_history + * @param _path_history New value to be moved in member path_history + */ +void etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::path_history( + etsi_its_cam_msgs::msg::PathHistory&& _path_history) +{ + m_path_history = std::move(_path_history); +} + +/*! + * @brief This function returns a constant reference to member path_history + * @return Constant reference to member path_history + */ +const etsi_its_cam_msgs::msg::PathHistory& etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::path_history() const +{ + return m_path_history; +} + +/*! + * @brief This function returns a reference to member path_history + * @return Reference to member path_history + */ +etsi_its_cam_msgs::msg::PathHistory& etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::path_history() +{ + return m_path_history; +} + +size_t etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.h new file mode 100644 index 00000000000..549dac222f6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.h @@ -0,0 +1,271 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file BasicVehicleContainerLowFrequency.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERLOWFREQUENCY_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERLOWFREQUENCY_H_ + +#include "VehicleRole.h" +#include "ExteriorLights.h" +#include "PathHistory.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(BasicVehicleContainerLowFrequency_SOURCE) +#define BasicVehicleContainerLowFrequency_DllAPI __declspec( dllexport ) +#else +#define BasicVehicleContainerLowFrequency_DllAPI __declspec( dllimport ) +#endif // BasicVehicleContainerLowFrequency_SOURCE +#else +#define BasicVehicleContainerLowFrequency_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define BasicVehicleContainerLowFrequency_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure BasicVehicleContainerLowFrequency defined by the user in the IDL file. + * @ingroup BASICVEHICLECONTAINERLOWFREQUENCY + */ + class BasicVehicleContainerLowFrequency + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport BasicVehicleContainerLowFrequency(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~BasicVehicleContainerLowFrequency(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency that will be copied. + */ + eProsima_user_DllExport BasicVehicleContainerLowFrequency( + const BasicVehicleContainerLowFrequency& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency that will be copied. + */ + eProsima_user_DllExport BasicVehicleContainerLowFrequency( + BasicVehicleContainerLowFrequency&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency that will be copied. + */ + eProsima_user_DllExport BasicVehicleContainerLowFrequency& operator =( + const BasicVehicleContainerLowFrequency& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency that will be copied. + */ + eProsima_user_DllExport BasicVehicleContainerLowFrequency& operator =( + BasicVehicleContainerLowFrequency&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency object to compare. + */ + eProsima_user_DllExport bool operator ==( + const BasicVehicleContainerLowFrequency& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency object to compare. + */ + eProsima_user_DllExport bool operator !=( + const BasicVehicleContainerLowFrequency& x) const; + + /*! + * @brief This function copies the value in member vehicle_role + * @param _vehicle_role New value to be copied in member vehicle_role + */ + eProsima_user_DllExport void vehicle_role( + const etsi_its_cam_msgs::msg::VehicleRole& _vehicle_role); + + /*! + * @brief This function moves the value in member vehicle_role + * @param _vehicle_role New value to be moved in member vehicle_role + */ + eProsima_user_DllExport void vehicle_role( + etsi_its_cam_msgs::msg::VehicleRole&& _vehicle_role); + + /*! + * @brief This function returns a constant reference to member vehicle_role + * @return Constant reference to member vehicle_role + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::VehicleRole& vehicle_role() const; + + /*! + * @brief This function returns a reference to member vehicle_role + * @return Reference to member vehicle_role + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::VehicleRole& vehicle_role(); + /*! + * @brief This function copies the value in member exterior_lights + * @param _exterior_lights New value to be copied in member exterior_lights + */ + eProsima_user_DllExport void exterior_lights( + const etsi_its_cam_msgs::msg::ExteriorLights& _exterior_lights); + + /*! + * @brief This function moves the value in member exterior_lights + * @param _exterior_lights New value to be moved in member exterior_lights + */ + eProsima_user_DllExport void exterior_lights( + etsi_its_cam_msgs::msg::ExteriorLights&& _exterior_lights); + + /*! + * @brief This function returns a constant reference to member exterior_lights + * @return Constant reference to member exterior_lights + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::ExteriorLights& exterior_lights() const; + + /*! + * @brief This function returns a reference to member exterior_lights + * @return Reference to member exterior_lights + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::ExteriorLights& exterior_lights(); + /*! + * @brief This function copies the value in member path_history + * @param _path_history New value to be copied in member path_history + */ + eProsima_user_DllExport void path_history( + const etsi_its_cam_msgs::msg::PathHistory& _path_history); + + /*! + * @brief This function moves the value in member path_history + * @param _path_history New value to be moved in member path_history + */ + eProsima_user_DllExport void path_history( + etsi_its_cam_msgs::msg::PathHistory&& _path_history); + + /*! + * @brief This function returns a constant reference to member path_history + * @return Constant reference to member path_history + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::PathHistory& path_history() const; + + /*! + * @brief This function returns a reference to member path_history + * @return Reference to member path_history + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::PathHistory& path_history(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::VehicleRole m_vehicle_role; + etsi_its_cam_msgs::msg::ExteriorLights m_exterior_lights; + etsi_its_cam_msgs::msg::PathHistory m_path_history; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERLOWFREQUENCY_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequencyPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequencyPubSubTypes.cxx new file mode 100644 index 00000000000..36cb0110bc0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequencyPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file BasicVehicleContainerLowFrequencyPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "BasicVehicleContainerLowFrequencyPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + BasicVehicleContainerLowFrequencyPubSubType::BasicVehicleContainerLowFrequencyPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::BasicVehicleContainerLowFrequency_"); + auto type_size = BasicVehicleContainerLowFrequency::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = BasicVehicleContainerLowFrequency::isKeyDefined(); + size_t keyLength = BasicVehicleContainerLowFrequency::getKeyMaxCdrSerializedSize() > 16 ? + BasicVehicleContainerLowFrequency::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + BasicVehicleContainerLowFrequencyPubSubType::~BasicVehicleContainerLowFrequencyPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool BasicVehicleContainerLowFrequencyPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + BasicVehicleContainerLowFrequency* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool BasicVehicleContainerLowFrequencyPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + BasicVehicleContainerLowFrequency* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function BasicVehicleContainerLowFrequencyPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* BasicVehicleContainerLowFrequencyPubSubType::createData() + { + return reinterpret_cast(new BasicVehicleContainerLowFrequency()); + } + + void BasicVehicleContainerLowFrequencyPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool BasicVehicleContainerLowFrequencyPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + BasicVehicleContainerLowFrequency* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + BasicVehicleContainerLowFrequency::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || BasicVehicleContainerLowFrequency::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequencyPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequencyPubSubTypes.h new file mode 100644 index 00000000000..fb7ccfbdf91 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequencyPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file BasicVehicleContainerLowFrequencyPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERLOWFREQUENCY_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERLOWFREQUENCY_PUBSUBTYPES_H_ + +#include +#include + +#include "BasicVehicleContainerLowFrequency.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated BasicVehicleContainerLowFrequency is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type BasicVehicleContainerLowFrequency defined by the user in the IDL file. + * @ingroup BASICVEHICLECONTAINERLOWFREQUENCY + */ + class BasicVehicleContainerLowFrequencyPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef BasicVehicleContainerLowFrequency type; + + eProsima_user_DllExport BasicVehicleContainerLowFrequencyPubSubType(); + + eProsima_user_DllExport virtual ~BasicVehicleContainerLowFrequencyPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERLOWFREQUENCY_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAM.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAM.cxx new file mode 100644 index 00000000000..7cd382b8490 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAM.cxx @@ -0,0 +1,238 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CAM.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CAM.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::CAM::CAM() +{ + // m_header com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@618c5d94 + + // m_cam com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@5b40ceb + + +} + +etsi_its_cam_msgs::msg::CAM::~CAM() +{ + +} + +etsi_its_cam_msgs::msg::CAM::CAM( + const CAM& x) +{ + m_header = x.m_header; + m_cam = x.m_cam; +} + +etsi_its_cam_msgs::msg::CAM::CAM( + CAM&& x) +{ + m_header = std::move(x.m_header); + m_cam = std::move(x.m_cam); +} + +etsi_its_cam_msgs::msg::CAM& etsi_its_cam_msgs::msg::CAM::operator =( + const CAM& x) +{ + + m_header = x.m_header; + m_cam = x.m_cam; + + return *this; +} + +etsi_its_cam_msgs::msg::CAM& etsi_its_cam_msgs::msg::CAM::operator =( + CAM&& x) +{ + + m_header = std::move(x.m_header); + m_cam = std::move(x.m_cam); + + return *this; +} + +bool etsi_its_cam_msgs::msg::CAM::operator ==( + const CAM& x) const +{ + + return (m_header == x.m_header && m_cam == x.m_cam); +} + +bool etsi_its_cam_msgs::msg::CAM::operator !=( + const CAM& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::CAM::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::ItsPduHeader::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::CoopAwareness::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::CAM::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::CAM& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::ItsPduHeader::getCdrSerializedSize(data.header(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::CoopAwareness::getCdrSerializedSize(data.cam(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::CAM::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_header; + scdr << m_cam; + +} + +void etsi_its_cam_msgs::msg::CAM::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_header; + dcdr >> m_cam; +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void etsi_its_cam_msgs::msg::CAM::header( + const etsi_its_cam_msgs::msg::ItsPduHeader& _header) +{ + m_header = _header; +} + +/*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ +void etsi_its_cam_msgs::msg::CAM::header( + etsi_its_cam_msgs::msg::ItsPduHeader&& _header) +{ + m_header = std::move(_header); +} + +/*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ +const etsi_its_cam_msgs::msg::ItsPduHeader& etsi_its_cam_msgs::msg::CAM::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +etsi_its_cam_msgs::msg::ItsPduHeader& etsi_its_cam_msgs::msg::CAM::header() +{ + return m_header; +} +/*! + * @brief This function copies the value in member cam + * @param _cam New value to be copied in member cam + */ +void etsi_its_cam_msgs::msg::CAM::cam( + const etsi_its_cam_msgs::msg::CoopAwareness& _cam) +{ + m_cam = _cam; +} + +/*! + * @brief This function moves the value in member cam + * @param _cam New value to be moved in member cam + */ +void etsi_its_cam_msgs::msg::CAM::cam( + etsi_its_cam_msgs::msg::CoopAwareness&& _cam) +{ + m_cam = std::move(_cam); +} + +/*! + * @brief This function returns a constant reference to member cam + * @return Constant reference to member cam + */ +const etsi_its_cam_msgs::msg::CoopAwareness& etsi_its_cam_msgs::msg::CAM::cam() const +{ + return m_cam; +} + +/*! + * @brief This function returns a reference to member cam + * @return Reference to member cam + */ +etsi_its_cam_msgs::msg::CoopAwareness& etsi_its_cam_msgs::msg::CAM::cam() +{ + return m_cam; +} + +size_t etsi_its_cam_msgs::msg::CAM::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::CAM::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::CAM::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAM.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAM.h new file mode 100644 index 00000000000..3d3156113cc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAM.h @@ -0,0 +1,244 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CAM.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAM_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAM_H_ + +#include "ItsPduHeader.h" +#include "CoopAwareness.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CAM_SOURCE) +#define CAM_DllAPI __declspec( dllexport ) +#else +#define CAM_DllAPI __declspec( dllimport ) +#endif // CAM_SOURCE +#else +#define CAM_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CAM_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure CAM defined by the user in the IDL file. + * @ingroup CAM + */ + class CAM + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CAM(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CAM(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::CAM that will be copied. + */ + eProsima_user_DllExport CAM( + const CAM& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::CAM that will be copied. + */ + eProsima_user_DllExport CAM( + CAM&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::CAM that will be copied. + */ + eProsima_user_DllExport CAM& operator =( + const CAM& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::CAM that will be copied. + */ + eProsima_user_DllExport CAM& operator =( + CAM&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::CAM object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CAM& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::CAM object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CAM& x) const; + + /*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ + eProsima_user_DllExport void header( + const etsi_its_cam_msgs::msg::ItsPduHeader& _header); + + /*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ + eProsima_user_DllExport void header( + etsi_its_cam_msgs::msg::ItsPduHeader&& _header); + + /*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::ItsPduHeader& header() const; + + /*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::ItsPduHeader& header(); + /*! + * @brief This function copies the value in member cam + * @param _cam New value to be copied in member cam + */ + eProsima_user_DllExport void cam( + const etsi_its_cam_msgs::msg::CoopAwareness& _cam); + + /*! + * @brief This function moves the value in member cam + * @param _cam New value to be moved in member cam + */ + eProsima_user_DllExport void cam( + etsi_its_cam_msgs::msg::CoopAwareness&& _cam); + + /*! + * @brief This function returns a constant reference to member cam + * @return Constant reference to member cam + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::CoopAwareness& cam() const; + + /*! + * @brief This function returns a reference to member cam + * @return Reference to member cam + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::CoopAwareness& cam(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::CAM& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::ItsPduHeader m_header; + etsi_its_cam_msgs::msg::CoopAwareness m_cam; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAM_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/ImagePubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAMPubSubTypes.cxx similarity index 71% rename from LibCarla/source/carla/ros2/types/ImagePubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAMPubSubTypes.cxx index cadfdf9908b..47720dfbe46 100644 --- a/LibCarla/source/carla/ros2/types/ImagePubSubTypes.cpp +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAMPubSubTypes.cxx @@ -13,36 +13,37 @@ // limitations under the License. /*! - * @file ImagePubSubTypes.cpp + * @file CAMPubSubTypes.cpp * This header file contains the implementation of the serialization functions. * * This file was generated by the tool fastcdrgen. */ + #include #include -#include "ImagePubSubTypes.h" +#include "CAMPubSubTypes.h" using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; -namespace sensor_msgs { +namespace etsi_its_cam_msgs { namespace msg { - ImagePubSubType::ImagePubSubType() + CAMPubSubType::CAMPubSubType() { - setName("sensor_msgs::msg::dds_::Image_"); - auto type_size = Image::getMaxCdrSerializedSize(); + setName("etsi_its_cam_msgs::msg::dds_::CAM_"); + auto type_size = CAM::getMaxCdrSerializedSize(); type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = Image::isKeyDefined(); - size_t keyLength = Image::getKeyMaxCdrSerializedSize() > 16 ? - Image::getKeyMaxCdrSerializedSize() : 16; + m_isGetKeyDefined = CAM::isKeyDefined(); + size_t keyLength = CAM::getKeyMaxCdrSerializedSize() > 16 ? + CAM::getKeyMaxCdrSerializedSize() : 16; m_keyBuffer = reinterpret_cast(malloc(keyLength)); memset(m_keyBuffer, 0, keyLength); } - ImagePubSubType::~ImagePubSubType() + CAMPubSubType::~CAMPubSubType() { if (m_keyBuffer != nullptr) { @@ -50,11 +51,11 @@ namespace sensor_msgs { } } - bool ImagePubSubType::serialize( + bool CAMPubSubType::serialize( void* data, SerializedPayload_t* payload) { - Image* p_type = static_cast(data); + CAM* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); @@ -63,18 +64,28 @@ namespace sensor_msgs { payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; // Serialize encapsulation ser.serialize_encapsulation(); - p_type->serialize(ser); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + // Get the serialized length payload->length = static_cast(ser.getSerializedDataLength()); return true; } - bool ImagePubSubType::deserialize( + bool CAMPubSubType::deserialize( SerializedPayload_t* payload, void* data) { //Convert DATA to pointer of your type - Image* p_type = static_cast(data); + CAM* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); @@ -86,33 +97,41 @@ namespace sensor_msgs { deser.read_encapsulation(); payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - // Deserialize the object. - p_type->deserialize(deser); + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + return true; } - std::function ImagePubSubType::getSerializedSizeProvider( + std::function CAMPubSubType::getSerializedSizeProvider( void* data) { return [data]() -> uint32_t { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + 4u /*encapsulation*/; }; } - void* ImagePubSubType::createData() + void* CAMPubSubType::createData() { - return reinterpret_cast(new Image()); + return reinterpret_cast(new CAM()); } - void ImagePubSubType::deleteData( + void CAMPubSubType::deleteData( void* data) { - delete(reinterpret_cast(data)); + delete(reinterpret_cast(data)); } - bool ImagePubSubType::getKey( + bool CAMPubSubType::getKey( void* data, InstanceHandle_t* handle, bool force_md5) @@ -122,16 +141,16 @@ namespace sensor_msgs { return false; } - Image* p_type = static_cast(data); + CAM* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - Image::getKeyMaxCdrSerializedSize()); + CAM::getKeyMaxCdrSerializedSize()); // Object that serializes the data. eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); p_type->serializeKey(ser); - if (force_md5 || Image::getKeyMaxCdrSerializedSize() > 16) + if (force_md5 || CAM::getKeyMaxCdrSerializedSize() > 16) { m_md5.init(); m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); @@ -150,5 +169,8 @@ namespace sensor_msgs { } return true; } + + } //End of namespace msg -} //End of namespace sensor_msgs + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/types/ClockPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAMPubSubTypes.h similarity index 80% rename from LibCarla/source/carla/ros2/types/ClockPubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAMPubSubTypes.h index e3cb8ca3b1d..f202cc39de2 100644 --- a/LibCarla/source/carla/ros2/types/ClockPubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAMPubSubTypes.h @@ -13,42 +13,43 @@ // limitations under the License. /*! - * @file ClockPubSubTypes.h + * @file CAMPubSubTypes.h * This header file contains the declaration of the serialization functions. * * This file was generated by the tool fastcdrgen. */ -#ifndef _FAST_DDS_GENERATED_ROSGRAPH_MSG_CLOCK_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_ROSGRAPH_MSG_CLOCK_PUBSUBTYPES_H_ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAM_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAM_PUBSUBTYPES_H_ #include #include -#include "Clock.h" +#include "CAM.h" #if !defined(GEN_API_VER) || (GEN_API_VER != 1) #error \ - Generated Clock is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. + Generated CAM is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. #endif // GEN_API_VER -namespace rosgraph +namespace etsi_its_cam_msgs { namespace msg { /*! - * @brief This class represents the TopicDataType of the type Clock defined by the user in the IDL file. - * @ingroup Clock + * @brief This class represents the TopicDataType of the type CAM defined by the user in the IDL file. + * @ingroup CAM */ - class ClockPubSubType : public eprosima::fastdds::dds::TopicDataType + class CAMPubSubType : public eprosima::fastdds::dds::TopicDataType { public: - typedef Clock type; + typedef CAM type; - eProsima_user_DllExport ClockPubSubType(); + eProsima_user_DllExport CAMPubSubType(); - eProsima_user_DllExport virtual ~ClockPubSubType() override; + eProsima_user_DllExport virtual ~CAMPubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -96,10 +97,11 @@ namespace rosgraph } #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; unsigned char* m_keyBuffer; }; } } -#endif // _FAST_DDS_GENERATED_ROSGRAPH_MSG_CLOCK_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAM_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParameters.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParameters.cxx new file mode 100644 index 00000000000..7323b0c6814 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParameters.cxx @@ -0,0 +1,420 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CamParameters.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CamParameters.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::CamParameters::CamParameters() +{ + // m_basic_container com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@773cbf4f + + // m_high_frequency_container com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@6b54655f + + // m_low_frequency_container com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@665e9289 + + // m_low_frequency_container_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@7d3430a7 + m_low_frequency_container_is_present = false; + // m_special_vehicle_container com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@6f603e89 + + // m_special_vehicle_container_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@2756c0a7 + m_special_vehicle_container_is_present = false; + +} + +etsi_its_cam_msgs::msg::CamParameters::~CamParameters() +{ + + + + + +} + +etsi_its_cam_msgs::msg::CamParameters::CamParameters( + const CamParameters& x) +{ + m_basic_container = x.m_basic_container; + m_high_frequency_container = x.m_high_frequency_container; + m_low_frequency_container = x.m_low_frequency_container; + m_low_frequency_container_is_present = x.m_low_frequency_container_is_present; + m_special_vehicle_container = x.m_special_vehicle_container; + m_special_vehicle_container_is_present = x.m_special_vehicle_container_is_present; +} + +etsi_its_cam_msgs::msg::CamParameters::CamParameters( + CamParameters&& x) +{ + m_basic_container = std::move(x.m_basic_container); + m_high_frequency_container = std::move(x.m_high_frequency_container); + m_low_frequency_container = std::move(x.m_low_frequency_container); + m_low_frequency_container_is_present = x.m_low_frequency_container_is_present; + m_special_vehicle_container = std::move(x.m_special_vehicle_container); + m_special_vehicle_container_is_present = x.m_special_vehicle_container_is_present; +} + +etsi_its_cam_msgs::msg::CamParameters& etsi_its_cam_msgs::msg::CamParameters::operator =( + const CamParameters& x) +{ + + m_basic_container = x.m_basic_container; + m_high_frequency_container = x.m_high_frequency_container; + m_low_frequency_container = x.m_low_frequency_container; + m_low_frequency_container_is_present = x.m_low_frequency_container_is_present; + m_special_vehicle_container = x.m_special_vehicle_container; + m_special_vehicle_container_is_present = x.m_special_vehicle_container_is_present; + + return *this; +} + +etsi_its_cam_msgs::msg::CamParameters& etsi_its_cam_msgs::msg::CamParameters::operator =( + CamParameters&& x) +{ + + m_basic_container = std::move(x.m_basic_container); + m_high_frequency_container = std::move(x.m_high_frequency_container); + m_low_frequency_container = std::move(x.m_low_frequency_container); + m_low_frequency_container_is_present = x.m_low_frequency_container_is_present; + m_special_vehicle_container = std::move(x.m_special_vehicle_container); + m_special_vehicle_container_is_present = x.m_special_vehicle_container_is_present; + + return *this; +} + +bool etsi_its_cam_msgs::msg::CamParameters::operator ==( + const CamParameters& x) const +{ + + return (m_basic_container == x.m_basic_container && m_high_frequency_container == x.m_high_frequency_container && m_low_frequency_container == x.m_low_frequency_container && m_low_frequency_container_is_present == x.m_low_frequency_container_is_present && m_special_vehicle_container == x.m_special_vehicle_container && m_special_vehicle_container_is_present == x.m_special_vehicle_container_is_present); +} + +bool etsi_its_cam_msgs::msg::CamParameters::operator !=( + const CamParameters& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::CamParameters::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::BasicContainer::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::HighFrequencyContainer::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::LowFrequencyContainer::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::SpecialVehicleContainer::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::CamParameters::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::CamParameters& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::BasicContainer::getCdrSerializedSize(data.basic_container(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::HighFrequencyContainer::getCdrSerializedSize(data.high_frequency_container(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::LowFrequencyContainer::getCdrSerializedSize(data.low_frequency_container(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::SpecialVehicleContainer::getCdrSerializedSize(data.special_vehicle_container(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::CamParameters::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_basic_container; + scdr << m_high_frequency_container; + scdr << m_low_frequency_container; + scdr << m_low_frequency_container_is_present; + scdr << m_special_vehicle_container; + scdr << m_special_vehicle_container_is_present; + +} + +void etsi_its_cam_msgs::msg::CamParameters::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_basic_container; + dcdr >> m_high_frequency_container; + dcdr >> m_low_frequency_container; + dcdr >> m_low_frequency_container_is_present; + dcdr >> m_special_vehicle_container; + dcdr >> m_special_vehicle_container_is_present; +} + +/*! + * @brief This function copies the value in member basic_container + * @param _basic_container New value to be copied in member basic_container + */ +void etsi_its_cam_msgs::msg::CamParameters::basic_container( + const etsi_its_cam_msgs::msg::BasicContainer& _basic_container) +{ + m_basic_container = _basic_container; +} + +/*! + * @brief This function moves the value in member basic_container + * @param _basic_container New value to be moved in member basic_container + */ +void etsi_its_cam_msgs::msg::CamParameters::basic_container( + etsi_its_cam_msgs::msg::BasicContainer&& _basic_container) +{ + m_basic_container = std::move(_basic_container); +} + +/*! + * @brief This function returns a constant reference to member basic_container + * @return Constant reference to member basic_container + */ +const etsi_its_cam_msgs::msg::BasicContainer& etsi_its_cam_msgs::msg::CamParameters::basic_container() const +{ + return m_basic_container; +} + +/*! + * @brief This function returns a reference to member basic_container + * @return Reference to member basic_container + */ +etsi_its_cam_msgs::msg::BasicContainer& etsi_its_cam_msgs::msg::CamParameters::basic_container() +{ + return m_basic_container; +} +/*! + * @brief This function copies the value in member high_frequency_container + * @param _high_frequency_container New value to be copied in member high_frequency_container + */ +void etsi_its_cam_msgs::msg::CamParameters::high_frequency_container( + const etsi_its_cam_msgs::msg::HighFrequencyContainer& _high_frequency_container) +{ + m_high_frequency_container = _high_frequency_container; +} + +/*! + * @brief This function moves the value in member high_frequency_container + * @param _high_frequency_container New value to be moved in member high_frequency_container + */ +void etsi_its_cam_msgs::msg::CamParameters::high_frequency_container( + etsi_its_cam_msgs::msg::HighFrequencyContainer&& _high_frequency_container) +{ + m_high_frequency_container = std::move(_high_frequency_container); +} + +/*! + * @brief This function returns a constant reference to member high_frequency_container + * @return Constant reference to member high_frequency_container + */ +const etsi_its_cam_msgs::msg::HighFrequencyContainer& etsi_its_cam_msgs::msg::CamParameters::high_frequency_container() const +{ + return m_high_frequency_container; +} + +/*! + * @brief This function returns a reference to member high_frequency_container + * @return Reference to member high_frequency_container + */ +etsi_its_cam_msgs::msg::HighFrequencyContainer& etsi_its_cam_msgs::msg::CamParameters::high_frequency_container() +{ + return m_high_frequency_container; +} +/*! + * @brief This function copies the value in member low_frequency_container + * @param _low_frequency_container New value to be copied in member low_frequency_container + */ +void etsi_its_cam_msgs::msg::CamParameters::low_frequency_container( + const etsi_its_cam_msgs::msg::LowFrequencyContainer& _low_frequency_container) +{ + m_low_frequency_container = _low_frequency_container; +} + +/*! + * @brief This function moves the value in member low_frequency_container + * @param _low_frequency_container New value to be moved in member low_frequency_container + */ +void etsi_its_cam_msgs::msg::CamParameters::low_frequency_container( + etsi_its_cam_msgs::msg::LowFrequencyContainer&& _low_frequency_container) +{ + m_low_frequency_container = std::move(_low_frequency_container); +} + +/*! + * @brief This function returns a constant reference to member low_frequency_container + * @return Constant reference to member low_frequency_container + */ +const etsi_its_cam_msgs::msg::LowFrequencyContainer& etsi_its_cam_msgs::msg::CamParameters::low_frequency_container() const +{ + return m_low_frequency_container; +} + +/*! + * @brief This function returns a reference to member low_frequency_container + * @return Reference to member low_frequency_container + */ +etsi_its_cam_msgs::msg::LowFrequencyContainer& etsi_its_cam_msgs::msg::CamParameters::low_frequency_container() +{ + return m_low_frequency_container; +} +/*! + * @brief This function sets a value in member low_frequency_container_is_present + * @param _low_frequency_container_is_present New value for member low_frequency_container_is_present + */ +void etsi_its_cam_msgs::msg::CamParameters::low_frequency_container_is_present( + bool _low_frequency_container_is_present) +{ + m_low_frequency_container_is_present = _low_frequency_container_is_present; +} + +/*! + * @brief This function returns the value of member low_frequency_container_is_present + * @return Value of member low_frequency_container_is_present + */ +bool etsi_its_cam_msgs::msg::CamParameters::low_frequency_container_is_present() const +{ + return m_low_frequency_container_is_present; +} + +/*! + * @brief This function returns a reference to member low_frequency_container_is_present + * @return Reference to member low_frequency_container_is_present + */ +bool& etsi_its_cam_msgs::msg::CamParameters::low_frequency_container_is_present() +{ + return m_low_frequency_container_is_present; +} + +/*! + * @brief This function copies the value in member special_vehicle_container + * @param _special_vehicle_container New value to be copied in member special_vehicle_container + */ +void etsi_its_cam_msgs::msg::CamParameters::special_vehicle_container( + const etsi_its_cam_msgs::msg::SpecialVehicleContainer& _special_vehicle_container) +{ + m_special_vehicle_container = _special_vehicle_container; +} + +/*! + * @brief This function moves the value in member special_vehicle_container + * @param _special_vehicle_container New value to be moved in member special_vehicle_container + */ +void etsi_its_cam_msgs::msg::CamParameters::special_vehicle_container( + etsi_its_cam_msgs::msg::SpecialVehicleContainer&& _special_vehicle_container) +{ + m_special_vehicle_container = std::move(_special_vehicle_container); +} + +/*! + * @brief This function returns a constant reference to member special_vehicle_container + * @return Constant reference to member special_vehicle_container + */ +const etsi_its_cam_msgs::msg::SpecialVehicleContainer& etsi_its_cam_msgs::msg::CamParameters::special_vehicle_container() const +{ + return m_special_vehicle_container; +} + +/*! + * @brief This function returns a reference to member special_vehicle_container + * @return Reference to member special_vehicle_container + */ +etsi_its_cam_msgs::msg::SpecialVehicleContainer& etsi_its_cam_msgs::msg::CamParameters::special_vehicle_container() +{ + return m_special_vehicle_container; +} +/*! + * @brief This function sets a value in member special_vehicle_container_is_present + * @param _special_vehicle_container_is_present New value for member special_vehicle_container_is_present + */ +void etsi_its_cam_msgs::msg::CamParameters::special_vehicle_container_is_present( + bool _special_vehicle_container_is_present) +{ + m_special_vehicle_container_is_present = _special_vehicle_container_is_present; +} + +/*! + * @brief This function returns the value of member special_vehicle_container_is_present + * @return Value of member special_vehicle_container_is_present + */ +bool etsi_its_cam_msgs::msg::CamParameters::special_vehicle_container_is_present() const +{ + return m_special_vehicle_container_is_present; +} + +/*! + * @brief This function returns a reference to member special_vehicle_container_is_present + * @return Reference to member special_vehicle_container_is_present + */ +bool& etsi_its_cam_msgs::msg::CamParameters::special_vehicle_container_is_present() +{ + return m_special_vehicle_container_is_present; +} + + +size_t etsi_its_cam_msgs::msg::CamParameters::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::CamParameters::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::CamParameters::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParameters.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParameters.h new file mode 100644 index 00000000000..b30a7e5a331 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParameters.h @@ -0,0 +1,338 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CamParameters.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMPARAMETERS_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMPARAMETERS_H_ + +#include "SpecialVehicleContainer.h" +#include "BasicContainer.h" +#include "HighFrequencyContainer.h" +#include "LowFrequencyContainer.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CamParameters_SOURCE) +#define CamParameters_DllAPI __declspec( dllexport ) +#else +#define CamParameters_DllAPI __declspec( dllimport ) +#endif // CamParameters_SOURCE +#else +#define CamParameters_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CamParameters_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure CamParameters defined by the user in the IDL file. + * @ingroup CAMPARAMETERS + */ + class CamParameters + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CamParameters(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CamParameters(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::CamParameters that will be copied. + */ + eProsima_user_DllExport CamParameters( + const CamParameters& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::CamParameters that will be copied. + */ + eProsima_user_DllExport CamParameters( + CamParameters&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::CamParameters that will be copied. + */ + eProsima_user_DllExport CamParameters& operator =( + const CamParameters& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::CamParameters that will be copied. + */ + eProsima_user_DllExport CamParameters& operator =( + CamParameters&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::CamParameters object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CamParameters& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::CamParameters object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CamParameters& x) const; + + /*! + * @brief This function copies the value in member basic_container + * @param _basic_container New value to be copied in member basic_container + */ + eProsima_user_DllExport void basic_container( + const etsi_its_cam_msgs::msg::BasicContainer& _basic_container); + + /*! + * @brief This function moves the value in member basic_container + * @param _basic_container New value to be moved in member basic_container + */ + eProsima_user_DllExport void basic_container( + etsi_its_cam_msgs::msg::BasicContainer&& _basic_container); + + /*! + * @brief This function returns a constant reference to member basic_container + * @return Constant reference to member basic_container + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::BasicContainer& basic_container() const; + + /*! + * @brief This function returns a reference to member basic_container + * @return Reference to member basic_container + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::BasicContainer& basic_container(); + /*! + * @brief This function copies the value in member high_frequency_container + * @param _high_frequency_container New value to be copied in member high_frequency_container + */ + eProsima_user_DllExport void high_frequency_container( + const etsi_its_cam_msgs::msg::HighFrequencyContainer& _high_frequency_container); + + /*! + * @brief This function moves the value in member high_frequency_container + * @param _high_frequency_container New value to be moved in member high_frequency_container + */ + eProsima_user_DllExport void high_frequency_container( + etsi_its_cam_msgs::msg::HighFrequencyContainer&& _high_frequency_container); + + /*! + * @brief This function returns a constant reference to member high_frequency_container + * @return Constant reference to member high_frequency_container + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::HighFrequencyContainer& high_frequency_container() const; + + /*! + * @brief This function returns a reference to member high_frequency_container + * @return Reference to member high_frequency_container + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::HighFrequencyContainer& high_frequency_container(); + /*! + * @brief This function copies the value in member low_frequency_container + * @param _low_frequency_container New value to be copied in member low_frequency_container + */ + eProsima_user_DllExport void low_frequency_container( + const etsi_its_cam_msgs::msg::LowFrequencyContainer& _low_frequency_container); + + /*! + * @brief This function moves the value in member low_frequency_container + * @param _low_frequency_container New value to be moved in member low_frequency_container + */ + eProsima_user_DllExport void low_frequency_container( + etsi_its_cam_msgs::msg::LowFrequencyContainer&& _low_frequency_container); + + /*! + * @brief This function returns a constant reference to member low_frequency_container + * @return Constant reference to member low_frequency_container + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::LowFrequencyContainer& low_frequency_container() const; + + /*! + * @brief This function returns a reference to member low_frequency_container + * @return Reference to member low_frequency_container + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::LowFrequencyContainer& low_frequency_container(); + /*! + * @brief This function sets a value in member low_frequency_container_is_present + * @param _low_frequency_container_is_present New value for member low_frequency_container_is_present + */ + eProsima_user_DllExport void low_frequency_container_is_present( + bool _low_frequency_container_is_present); + + /*! + * @brief This function returns the value of member low_frequency_container_is_present + * @return Value of member low_frequency_container_is_present + */ + eProsima_user_DllExport bool low_frequency_container_is_present() const; + + /*! + * @brief This function returns a reference to member low_frequency_container_is_present + * @return Reference to member low_frequency_container_is_present + */ + eProsima_user_DllExport bool& low_frequency_container_is_present(); + + /*! + * @brief This function copies the value in member special_vehicle_container + * @param _special_vehicle_container New value to be copied in member special_vehicle_container + */ + eProsima_user_DllExport void special_vehicle_container( + const etsi_its_cam_msgs::msg::SpecialVehicleContainer& _special_vehicle_container); + + /*! + * @brief This function moves the value in member special_vehicle_container + * @param _special_vehicle_container New value to be moved in member special_vehicle_container + */ + eProsima_user_DllExport void special_vehicle_container( + etsi_its_cam_msgs::msg::SpecialVehicleContainer&& _special_vehicle_container); + + /*! + * @brief This function returns a constant reference to member special_vehicle_container + * @return Constant reference to member special_vehicle_container + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::SpecialVehicleContainer& special_vehicle_container() const; + + /*! + * @brief This function returns a reference to member special_vehicle_container + * @return Reference to member special_vehicle_container + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::SpecialVehicleContainer& special_vehicle_container(); + /*! + * @brief This function sets a value in member special_vehicle_container_is_present + * @param _special_vehicle_container_is_present New value for member special_vehicle_container_is_present + */ + eProsima_user_DllExport void special_vehicle_container_is_present( + bool _special_vehicle_container_is_present); + + /*! + * @brief This function returns the value of member special_vehicle_container_is_present + * @return Value of member special_vehicle_container_is_present + */ + eProsima_user_DllExport bool special_vehicle_container_is_present() const; + + /*! + * @brief This function returns a reference to member special_vehicle_container_is_present + * @return Reference to member special_vehicle_container_is_present + */ + eProsima_user_DllExport bool& special_vehicle_container_is_present(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::CamParameters& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::BasicContainer m_basic_container; + etsi_its_cam_msgs::msg::HighFrequencyContainer m_high_frequency_container; + etsi_its_cam_msgs::msg::LowFrequencyContainer m_low_frequency_container; + bool m_low_frequency_container_is_present; + etsi_its_cam_msgs::msg::SpecialVehicleContainer m_special_vehicle_container; + bool m_special_vehicle_container_is_present; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMPARAMETERS_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParametersPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParametersPubSubTypes.cxx new file mode 100644 index 00000000000..abfad39c34c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParametersPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CamParametersPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CamParametersPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + CamParametersPubSubType::CamParametersPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::CamParameters_"); + auto type_size = CamParameters::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CamParameters::isKeyDefined(); + size_t keyLength = CamParameters::getKeyMaxCdrSerializedSize() > 16 ? + CamParameters::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CamParametersPubSubType::~CamParametersPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CamParametersPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CamParameters* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CamParametersPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CamParameters* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CamParametersPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CamParametersPubSubType::createData() + { + return reinterpret_cast(new CamParameters()); + } + + void CamParametersPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CamParametersPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CamParameters* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CamParameters::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CamParameters::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParametersPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParametersPubSubTypes.h new file mode 100644 index 00000000000..ea7f45e0f65 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParametersPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CamParametersPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMPARAMETERS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMPARAMETERS_PUBSUBTYPES_H_ + +#include +#include + +#include "CamParameters.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CamParameters is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CamParameters defined by the user in the IDL file. + * @ingroup CAMPARAMETERS + */ + class CamParametersPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CamParameters type; + + eProsima_user_DllExport CamParametersPubSubType(); + + eProsima_user_DllExport virtual ~CamParametersPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMPARAMETERS_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCode.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCode.cxx new file mode 100644 index 00000000000..4e23fcb059d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCode.cxx @@ -0,0 +1,238 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CauseCode.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CauseCode.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::CauseCode::CauseCode() +{ + // m_cause_code com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@bc57b40 + + // m_sub_cause_code com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@1b5bc39d + + +} + +etsi_its_cam_msgs::msg::CauseCode::~CauseCode() +{ + +} + +etsi_its_cam_msgs::msg::CauseCode::CauseCode( + const CauseCode& x) +{ + m_cause_code = x.m_cause_code; + m_sub_cause_code = x.m_sub_cause_code; +} + +etsi_its_cam_msgs::msg::CauseCode::CauseCode( + CauseCode&& x) +{ + m_cause_code = std::move(x.m_cause_code); + m_sub_cause_code = std::move(x.m_sub_cause_code); +} + +etsi_its_cam_msgs::msg::CauseCode& etsi_its_cam_msgs::msg::CauseCode::operator =( + const CauseCode& x) +{ + + m_cause_code = x.m_cause_code; + m_sub_cause_code = x.m_sub_cause_code; + + return *this; +} + +etsi_its_cam_msgs::msg::CauseCode& etsi_its_cam_msgs::msg::CauseCode::operator =( + CauseCode&& x) +{ + + m_cause_code = std::move(x.m_cause_code); + m_sub_cause_code = std::move(x.m_sub_cause_code); + + return *this; +} + +bool etsi_its_cam_msgs::msg::CauseCode::operator ==( + const CauseCode& x) const +{ + + return (m_cause_code == x.m_cause_code && m_sub_cause_code == x.m_sub_cause_code); +} + +bool etsi_its_cam_msgs::msg::CauseCode::operator !=( + const CauseCode& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::CauseCode::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::CauseCodeType::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::SubCauseCodeType::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::CauseCode::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::CauseCode& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::CauseCodeType::getCdrSerializedSize(data.cause_code(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::SubCauseCodeType::getCdrSerializedSize(data.sub_cause_code(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::CauseCode::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_cause_code; + scdr << m_sub_cause_code; + +} + +void etsi_its_cam_msgs::msg::CauseCode::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_cause_code; + dcdr >> m_sub_cause_code; +} + +/*! + * @brief This function copies the value in member cause_code + * @param _cause_code New value to be copied in member cause_code + */ +void etsi_its_cam_msgs::msg::CauseCode::cause_code( + const etsi_its_cam_msgs::msg::CauseCodeType& _cause_code) +{ + m_cause_code = _cause_code; +} + +/*! + * @brief This function moves the value in member cause_code + * @param _cause_code New value to be moved in member cause_code + */ +void etsi_its_cam_msgs::msg::CauseCode::cause_code( + etsi_its_cam_msgs::msg::CauseCodeType&& _cause_code) +{ + m_cause_code = std::move(_cause_code); +} + +/*! + * @brief This function returns a constant reference to member cause_code + * @return Constant reference to member cause_code + */ +const etsi_its_cam_msgs::msg::CauseCodeType& etsi_its_cam_msgs::msg::CauseCode::cause_code() const +{ + return m_cause_code; +} + +/*! + * @brief This function returns a reference to member cause_code + * @return Reference to member cause_code + */ +etsi_its_cam_msgs::msg::CauseCodeType& etsi_its_cam_msgs::msg::CauseCode::cause_code() +{ + return m_cause_code; +} +/*! + * @brief This function copies the value in member sub_cause_code + * @param _sub_cause_code New value to be copied in member sub_cause_code + */ +void etsi_its_cam_msgs::msg::CauseCode::sub_cause_code( + const etsi_its_cam_msgs::msg::SubCauseCodeType& _sub_cause_code) +{ + m_sub_cause_code = _sub_cause_code; +} + +/*! + * @brief This function moves the value in member sub_cause_code + * @param _sub_cause_code New value to be moved in member sub_cause_code + */ +void etsi_its_cam_msgs::msg::CauseCode::sub_cause_code( + etsi_its_cam_msgs::msg::SubCauseCodeType&& _sub_cause_code) +{ + m_sub_cause_code = std::move(_sub_cause_code); +} + +/*! + * @brief This function returns a constant reference to member sub_cause_code + * @return Constant reference to member sub_cause_code + */ +const etsi_its_cam_msgs::msg::SubCauseCodeType& etsi_its_cam_msgs::msg::CauseCode::sub_cause_code() const +{ + return m_sub_cause_code; +} + +/*! + * @brief This function returns a reference to member sub_cause_code + * @return Reference to member sub_cause_code + */ +etsi_its_cam_msgs::msg::SubCauseCodeType& etsi_its_cam_msgs::msg::CauseCode::sub_cause_code() +{ + return m_sub_cause_code; +} + +size_t etsi_its_cam_msgs::msg::CauseCode::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::CauseCode::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::CauseCode::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCode.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCode.h new file mode 100644 index 00000000000..4533dc8dbc3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCode.h @@ -0,0 +1,244 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CauseCode.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODE_H_ + +#include "SubCauseCodeType.h" +#include "CauseCodeType.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CauseCode_SOURCE) +#define CauseCode_DllAPI __declspec( dllexport ) +#else +#define CauseCode_DllAPI __declspec( dllimport ) +#endif // CauseCode_SOURCE +#else +#define CauseCode_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CauseCode_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure CauseCode defined by the user in the IDL file. + * @ingroup CAUSECODE + */ + class CauseCode + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CauseCode(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CauseCode(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::CauseCode that will be copied. + */ + eProsima_user_DllExport CauseCode( + const CauseCode& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::CauseCode that will be copied. + */ + eProsima_user_DllExport CauseCode( + CauseCode&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::CauseCode that will be copied. + */ + eProsima_user_DllExport CauseCode& operator =( + const CauseCode& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::CauseCode that will be copied. + */ + eProsima_user_DllExport CauseCode& operator =( + CauseCode&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::CauseCode object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CauseCode& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::CauseCode object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CauseCode& x) const; + + /*! + * @brief This function copies the value in member cause_code + * @param _cause_code New value to be copied in member cause_code + */ + eProsima_user_DllExport void cause_code( + const etsi_its_cam_msgs::msg::CauseCodeType& _cause_code); + + /*! + * @brief This function moves the value in member cause_code + * @param _cause_code New value to be moved in member cause_code + */ + eProsima_user_DllExport void cause_code( + etsi_its_cam_msgs::msg::CauseCodeType&& _cause_code); + + /*! + * @brief This function returns a constant reference to member cause_code + * @return Constant reference to member cause_code + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::CauseCodeType& cause_code() const; + + /*! + * @brief This function returns a reference to member cause_code + * @return Reference to member cause_code + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::CauseCodeType& cause_code(); + /*! + * @brief This function copies the value in member sub_cause_code + * @param _sub_cause_code New value to be copied in member sub_cause_code + */ + eProsima_user_DllExport void sub_cause_code( + const etsi_its_cam_msgs::msg::SubCauseCodeType& _sub_cause_code); + + /*! + * @brief This function moves the value in member sub_cause_code + * @param _sub_cause_code New value to be moved in member sub_cause_code + */ + eProsima_user_DllExport void sub_cause_code( + etsi_its_cam_msgs::msg::SubCauseCodeType&& _sub_cause_code); + + /*! + * @brief This function returns a constant reference to member sub_cause_code + * @return Constant reference to member sub_cause_code + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::SubCauseCodeType& sub_cause_code() const; + + /*! + * @brief This function returns a reference to member sub_cause_code + * @return Reference to member sub_cause_code + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::SubCauseCodeType& sub_cause_code(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::CauseCode& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::CauseCodeType m_cause_code; + etsi_its_cam_msgs::msg::SubCauseCodeType m_sub_cause_code; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodePubSubTypes.cxx new file mode 100644 index 00000000000..cc0a7168c68 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodePubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CauseCodePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CauseCodePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + CauseCodePubSubType::CauseCodePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::CauseCode_"); + auto type_size = CauseCode::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CauseCode::isKeyDefined(); + size_t keyLength = CauseCode::getKeyMaxCdrSerializedSize() > 16 ? + CauseCode::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CauseCodePubSubType::~CauseCodePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CauseCodePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CauseCode* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CauseCodePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CauseCode* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CauseCodePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CauseCodePubSubType::createData() + { + return reinterpret_cast(new CauseCode()); + } + + void CauseCodePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CauseCodePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CauseCode* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CauseCode::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CauseCode::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/types/TFMessagePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodePubSubTypes.h similarity index 77% rename from LibCarla/source/carla/ros2/types/TFMessagePubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodePubSubTypes.h index 5dbd16037bf..995db83ecf8 100644 --- a/LibCarla/source/carla/ros2/types/TFMessagePubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodePubSubTypes.h @@ -13,45 +13,43 @@ // limitations under the License. /*! - * @file TFMessagePubSubTypes.h + * @file CauseCodePubSubTypes.h * This header file contains the declaration of the serialization functions. * * This file was generated by the tool fastcdrgen. */ -#ifndef _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGE_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGE_PUBSUBTYPES_H_ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODE_PUBSUBTYPES_H_ #include #include -#include "TFMessage.h" - -#include "TransformStampedPubSubTypes.h" +#include "CauseCode.h" #if !defined(GEN_API_VER) || (GEN_API_VER != 1) #error \ - Generated TFMessage is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. + Generated CauseCode is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. #endif // GEN_API_VER -namespace tf2_msgs +namespace etsi_its_cam_msgs { namespace msg { - /*! - * @brief This class represents the TopicDataType of the type TFMessage defined by the user in the IDL file. - * @ingroup TFMESSAGE + * @brief This class represents the TopicDataType of the type CauseCode defined by the user in the IDL file. + * @ingroup CAUSECODE */ - class TFMessagePubSubType : public eprosima::fastdds::dds::TopicDataType + class CauseCodePubSubType : public eprosima::fastdds::dds::TopicDataType { public: - typedef TFMessage type; + typedef CauseCode type; - eProsima_user_DllExport TFMessagePubSubType(); + eProsima_user_DllExport CauseCodePubSubType(); - eProsima_user_DllExport virtual ~TFMessagePubSubType() override; + eProsima_user_DllExport virtual ~CauseCodePubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -77,7 +75,7 @@ namespace tf2_msgs #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED eProsima_user_DllExport inline bool is_bounded() const override { - return false; + return true; } #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED @@ -85,7 +83,7 @@ namespace tf2_msgs #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN eProsima_user_DllExport inline bool is_plain() const override { - return false; + return true; } #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN @@ -94,15 +92,16 @@ namespace tf2_msgs eProsima_user_DllExport inline bool construct_sample( void* memory) const override { - (void)memory; - return false; + new (memory) CauseCode(); + return true; } #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; unsigned char* m_keyBuffer; }; } } -#endif // _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGE_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeType.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeType.cxx new file mode 100644 index 00000000000..4c64c12d3bc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeType.cxx @@ -0,0 +1,213 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CauseCodeType.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CauseCodeType.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +etsi_its_cam_msgs::msg::CauseCodeType::CauseCodeType() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@2ca47471 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::CauseCodeType::~CauseCodeType() +{ +} + +etsi_its_cam_msgs::msg::CauseCodeType::CauseCodeType( + const CauseCodeType& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::CauseCodeType::CauseCodeType( + CauseCodeType&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::CauseCodeType& etsi_its_cam_msgs::msg::CauseCodeType::operator =( + const CauseCodeType& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::CauseCodeType& etsi_its_cam_msgs::msg::CauseCodeType::operator =( + CauseCodeType&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::CauseCodeType::operator ==( + const CauseCodeType& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::CauseCodeType::operator !=( + const CauseCodeType& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::CauseCodeType::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::CauseCodeType::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::CauseCodeType& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::CauseCodeType::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::CauseCodeType::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::CauseCodeType::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::CauseCodeType::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::CauseCodeType::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::CauseCodeType::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::CauseCodeType::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::CauseCodeType::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeType.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeType.h new file mode 100644 index 00000000000..b1bb4a7e467 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeType.h @@ -0,0 +1,241 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CauseCodeType.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODETYPE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODETYPE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CauseCodeType_SOURCE) +#define CauseCodeType_DllAPI __declspec( dllexport ) +#else +#define CauseCodeType_DllAPI __declspec( dllimport ) +#endif // CauseCodeType_SOURCE +#else +#define CauseCodeType_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CauseCodeType_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace CauseCodeType_Constants { + const uint8_t MIN = 0; + const uint8_t MAX = 255; + const uint8_t RESERVED = 0; + const uint8_t TRAFFIC_CONDITION = 1; + const uint8_t ACCIDENT = 2; + const uint8_t ROADWORKS = 3; + const uint8_t IMPASSABILITY = 5; + const uint8_t ADVERSE_WEATHER_CONDITION_ADHESION = 6; + const uint8_t AQUAPLANNNING = 7; + const uint8_t HAZARDOUS_LOCATION_SURFACE_CONDITION = 9; + const uint8_t HAZARDOUS_LOCATION_OBSTACLE_ON_THE_ROAD = 10; + const uint8_t HAZARDOUS_LOCATION_ANIMAL_ON_THE_ROAD = 11; + const uint8_t HUMAN_PRESENCE_ON_THE_ROAD = 12; + const uint8_t WRONG_WAY_DRIVING = 14; + const uint8_t RESCUE_AND_RECOVERY_WORK_IN_PROGRESS = 15; + const uint8_t ADVERSE_WEATHER_CONDITION_EXTREME_WEATHER_CONDITION = 17; + const uint8_t ADVERSE_WEATHER_CONDITION_VISIBILITY = 18; + const uint8_t ADVERSE_WEATHER_CONDITION_PRECIPITATION = 19; + const uint8_t SLOW_VEHICLE = 26; + const uint8_t DANGEROUS_END_OF_QUEUE = 27; + const uint8_t VEHICLE_BREAKDOWN = 91; + const uint8_t POST_CRASH = 92; + const uint8_t HUMAN_PROBLEM = 93; + const uint8_t STATIONARY_VEHICLE = 94; + const uint8_t EMERGENCY_VEHICLE_APPROACHING = 95; + const uint8_t HAZARDOUS_LOCATION_DANGEROUS_CURVE = 96; + const uint8_t COLLISION_RISK = 97; + const uint8_t SIGNAL_VIOLATION = 98; + const uint8_t DANGEROUS_SITUATION = 99; + } // namespace CauseCodeType_Constants + /*! + * @brief This class represents the structure CauseCodeType defined by the user in the IDL file. + * @ingroup CAUSECODETYPE + */ + class CauseCodeType + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CauseCodeType(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CauseCodeType(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::CauseCodeType that will be copied. + */ + eProsima_user_DllExport CauseCodeType( + const CauseCodeType& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::CauseCodeType that will be copied. + */ + eProsima_user_DllExport CauseCodeType( + CauseCodeType&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::CauseCodeType that will be copied. + */ + eProsima_user_DllExport CauseCodeType& operator =( + const CauseCodeType& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::CauseCodeType that will be copied. + */ + eProsima_user_DllExport CauseCodeType& operator =( + CauseCodeType&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::CauseCodeType object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CauseCodeType& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::CauseCodeType object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CauseCodeType& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::CauseCodeType& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODETYPE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeTypePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeTypePubSubTypes.cxx new file mode 100644 index 00000000000..fb783704eb1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeTypePubSubTypes.cxx @@ -0,0 +1,208 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CauseCodeTypePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CauseCodeTypePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace CauseCodeType_Constants { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + } //End of namespace CauseCodeType_Constants + CauseCodeTypePubSubType::CauseCodeTypePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::CauseCodeType_"); + auto type_size = CauseCodeType::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CauseCodeType::isKeyDefined(); + size_t keyLength = CauseCodeType::getKeyMaxCdrSerializedSize() > 16 ? + CauseCodeType::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CauseCodeTypePubSubType::~CauseCodeTypePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CauseCodeTypePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CauseCodeType* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CauseCodeTypePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CauseCodeType* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CauseCodeTypePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CauseCodeTypePubSubType::createData() + { + return reinterpret_cast(new CauseCodeType()); + } + + void CauseCodeTypePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CauseCodeTypePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CauseCodeType* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CauseCodeType::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CauseCodeType::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeTypePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeTypePubSubTypes.h new file mode 100644 index 00000000000..d4850117008 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeTypePubSubTypes.h @@ -0,0 +1,139 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CauseCodeTypePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODETYPE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODETYPE_PUBSUBTYPES_H_ + +#include +#include + +#include "CauseCodeType.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CauseCodeType is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace CauseCodeType_Constants + { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type CauseCodeType defined by the user in the IDL file. + * @ingroup CAUSECODETYPE + */ + class CauseCodeTypePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CauseCodeType type; + + eProsima_user_DllExport CauseCodeTypePubSubType(); + + eProsima_user_DllExport virtual ~CauseCodeTypePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) CauseCodeType(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODETYPE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZone.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZone.cxx new file mode 100644 index 00000000000..4e4ec3a12c9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZone.cxx @@ -0,0 +1,329 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CenDsrcTollingZone.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CenDsrcTollingZone.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::CenDsrcTollingZone::CenDsrcTollingZone() +{ + // m_protected_zone_latitude com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@3a627c80 + + // m_protected_zone_longitude com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@49aa766b + + // m_cen_dsrc_tolling_zone_id com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@963176 + + // m_cen_dsrc_tolling_zone_id_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@65004ff6 + m_cen_dsrc_tolling_zone_id_is_present = false; + +} + +etsi_its_cam_msgs::msg::CenDsrcTollingZone::~CenDsrcTollingZone() +{ + + + +} + +etsi_its_cam_msgs::msg::CenDsrcTollingZone::CenDsrcTollingZone( + const CenDsrcTollingZone& x) +{ + m_protected_zone_latitude = x.m_protected_zone_latitude; + m_protected_zone_longitude = x.m_protected_zone_longitude; + m_cen_dsrc_tolling_zone_id = x.m_cen_dsrc_tolling_zone_id; + m_cen_dsrc_tolling_zone_id_is_present = x.m_cen_dsrc_tolling_zone_id_is_present; +} + +etsi_its_cam_msgs::msg::CenDsrcTollingZone::CenDsrcTollingZone( + CenDsrcTollingZone&& x) +{ + m_protected_zone_latitude = std::move(x.m_protected_zone_latitude); + m_protected_zone_longitude = std::move(x.m_protected_zone_longitude); + m_cen_dsrc_tolling_zone_id = std::move(x.m_cen_dsrc_tolling_zone_id); + m_cen_dsrc_tolling_zone_id_is_present = x.m_cen_dsrc_tolling_zone_id_is_present; +} + +etsi_its_cam_msgs::msg::CenDsrcTollingZone& etsi_its_cam_msgs::msg::CenDsrcTollingZone::operator =( + const CenDsrcTollingZone& x) +{ + + m_protected_zone_latitude = x.m_protected_zone_latitude; + m_protected_zone_longitude = x.m_protected_zone_longitude; + m_cen_dsrc_tolling_zone_id = x.m_cen_dsrc_tolling_zone_id; + m_cen_dsrc_tolling_zone_id_is_present = x.m_cen_dsrc_tolling_zone_id_is_present; + + return *this; +} + +etsi_its_cam_msgs::msg::CenDsrcTollingZone& etsi_its_cam_msgs::msg::CenDsrcTollingZone::operator =( + CenDsrcTollingZone&& x) +{ + + m_protected_zone_latitude = std::move(x.m_protected_zone_latitude); + m_protected_zone_longitude = std::move(x.m_protected_zone_longitude); + m_cen_dsrc_tolling_zone_id = std::move(x.m_cen_dsrc_tolling_zone_id); + m_cen_dsrc_tolling_zone_id_is_present = x.m_cen_dsrc_tolling_zone_id_is_present; + + return *this; +} + +bool etsi_its_cam_msgs::msg::CenDsrcTollingZone::operator ==( + const CenDsrcTollingZone& x) const +{ + + return (m_protected_zone_latitude == x.m_protected_zone_latitude && m_protected_zone_longitude == x.m_protected_zone_longitude && m_cen_dsrc_tolling_zone_id == x.m_cen_dsrc_tolling_zone_id && m_cen_dsrc_tolling_zone_id_is_present == x.m_cen_dsrc_tolling_zone_id_is_present); +} + +bool etsi_its_cam_msgs::msg::CenDsrcTollingZone::operator !=( + const CenDsrcTollingZone& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::CenDsrcTollingZone::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::Latitude::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::Longitude::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::CenDsrcTollingZone::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::CenDsrcTollingZone& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::Latitude::getCdrSerializedSize(data.protected_zone_latitude(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::Longitude::getCdrSerializedSize(data.protected_zone_longitude(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::getCdrSerializedSize(data.cen_dsrc_tolling_zone_id(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::CenDsrcTollingZone::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_protected_zone_latitude; + scdr << m_protected_zone_longitude; + scdr << m_cen_dsrc_tolling_zone_id; + scdr << m_cen_dsrc_tolling_zone_id_is_present; + +} + +void etsi_its_cam_msgs::msg::CenDsrcTollingZone::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_protected_zone_latitude; + dcdr >> m_protected_zone_longitude; + dcdr >> m_cen_dsrc_tolling_zone_id; + dcdr >> m_cen_dsrc_tolling_zone_id_is_present; +} + +/*! + * @brief This function copies the value in member protected_zone_latitude + * @param _protected_zone_latitude New value to be copied in member protected_zone_latitude + */ +void etsi_its_cam_msgs::msg::CenDsrcTollingZone::protected_zone_latitude( + const etsi_its_cam_msgs::msg::Latitude& _protected_zone_latitude) +{ + m_protected_zone_latitude = _protected_zone_latitude; +} + +/*! + * @brief This function moves the value in member protected_zone_latitude + * @param _protected_zone_latitude New value to be moved in member protected_zone_latitude + */ +void etsi_its_cam_msgs::msg::CenDsrcTollingZone::protected_zone_latitude( + etsi_its_cam_msgs::msg::Latitude&& _protected_zone_latitude) +{ + m_protected_zone_latitude = std::move(_protected_zone_latitude); +} + +/*! + * @brief This function returns a constant reference to member protected_zone_latitude + * @return Constant reference to member protected_zone_latitude + */ +const etsi_its_cam_msgs::msg::Latitude& etsi_its_cam_msgs::msg::CenDsrcTollingZone::protected_zone_latitude() const +{ + return m_protected_zone_latitude; +} + +/*! + * @brief This function returns a reference to member protected_zone_latitude + * @return Reference to member protected_zone_latitude + */ +etsi_its_cam_msgs::msg::Latitude& etsi_its_cam_msgs::msg::CenDsrcTollingZone::protected_zone_latitude() +{ + return m_protected_zone_latitude; +} +/*! + * @brief This function copies the value in member protected_zone_longitude + * @param _protected_zone_longitude New value to be copied in member protected_zone_longitude + */ +void etsi_its_cam_msgs::msg::CenDsrcTollingZone::protected_zone_longitude( + const etsi_its_cam_msgs::msg::Longitude& _protected_zone_longitude) +{ + m_protected_zone_longitude = _protected_zone_longitude; +} + +/*! + * @brief This function moves the value in member protected_zone_longitude + * @param _protected_zone_longitude New value to be moved in member protected_zone_longitude + */ +void etsi_its_cam_msgs::msg::CenDsrcTollingZone::protected_zone_longitude( + etsi_its_cam_msgs::msg::Longitude&& _protected_zone_longitude) +{ + m_protected_zone_longitude = std::move(_protected_zone_longitude); +} + +/*! + * @brief This function returns a constant reference to member protected_zone_longitude + * @return Constant reference to member protected_zone_longitude + */ +const etsi_its_cam_msgs::msg::Longitude& etsi_its_cam_msgs::msg::CenDsrcTollingZone::protected_zone_longitude() const +{ + return m_protected_zone_longitude; +} + +/*! + * @brief This function returns a reference to member protected_zone_longitude + * @return Reference to member protected_zone_longitude + */ +etsi_its_cam_msgs::msg::Longitude& etsi_its_cam_msgs::msg::CenDsrcTollingZone::protected_zone_longitude() +{ + return m_protected_zone_longitude; +} +/*! + * @brief This function copies the value in member cen_dsrc_tolling_zone_id + * @param _cen_dsrc_tolling_zone_id New value to be copied in member cen_dsrc_tolling_zone_id + */ +void etsi_its_cam_msgs::msg::CenDsrcTollingZone::cen_dsrc_tolling_zone_id( + const etsi_its_cam_msgs::msg::CenDsrcTollingZoneID& _cen_dsrc_tolling_zone_id) +{ + m_cen_dsrc_tolling_zone_id = _cen_dsrc_tolling_zone_id; +} + +/*! + * @brief This function moves the value in member cen_dsrc_tolling_zone_id + * @param _cen_dsrc_tolling_zone_id New value to be moved in member cen_dsrc_tolling_zone_id + */ +void etsi_its_cam_msgs::msg::CenDsrcTollingZone::cen_dsrc_tolling_zone_id( + etsi_its_cam_msgs::msg::CenDsrcTollingZoneID&& _cen_dsrc_tolling_zone_id) +{ + m_cen_dsrc_tolling_zone_id = std::move(_cen_dsrc_tolling_zone_id); +} + +/*! + * @brief This function returns a constant reference to member cen_dsrc_tolling_zone_id + * @return Constant reference to member cen_dsrc_tolling_zone_id + */ +const etsi_its_cam_msgs::msg::CenDsrcTollingZoneID& etsi_its_cam_msgs::msg::CenDsrcTollingZone::cen_dsrc_tolling_zone_id() const +{ + return m_cen_dsrc_tolling_zone_id; +} + +/*! + * @brief This function returns a reference to member cen_dsrc_tolling_zone_id + * @return Reference to member cen_dsrc_tolling_zone_id + */ +etsi_its_cam_msgs::msg::CenDsrcTollingZoneID& etsi_its_cam_msgs::msg::CenDsrcTollingZone::cen_dsrc_tolling_zone_id() +{ + return m_cen_dsrc_tolling_zone_id; +} +/*! + * @brief This function sets a value in member cen_dsrc_tolling_zone_id_is_present + * @param _cen_dsrc_tolling_zone_id_is_present New value for member cen_dsrc_tolling_zone_id_is_present + */ +void etsi_its_cam_msgs::msg::CenDsrcTollingZone::cen_dsrc_tolling_zone_id_is_present( + bool _cen_dsrc_tolling_zone_id_is_present) +{ + m_cen_dsrc_tolling_zone_id_is_present = _cen_dsrc_tolling_zone_id_is_present; +} + +/*! + * @brief This function returns the value of member cen_dsrc_tolling_zone_id_is_present + * @return Value of member cen_dsrc_tolling_zone_id_is_present + */ +bool etsi_its_cam_msgs::msg::CenDsrcTollingZone::cen_dsrc_tolling_zone_id_is_present() const +{ + return m_cen_dsrc_tolling_zone_id_is_present; +} + +/*! + * @brief This function returns a reference to member cen_dsrc_tolling_zone_id_is_present + * @return Reference to member cen_dsrc_tolling_zone_id_is_present + */ +bool& etsi_its_cam_msgs::msg::CenDsrcTollingZone::cen_dsrc_tolling_zone_id_is_present() +{ + return m_cen_dsrc_tolling_zone_id_is_present; +} + + +size_t etsi_its_cam_msgs::msg::CenDsrcTollingZone::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::CenDsrcTollingZone::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::CenDsrcTollingZone::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZone.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZone.h new file mode 100644 index 00000000000..8ebadc85c1a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZone.h @@ -0,0 +1,291 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CenDsrcTollingZone.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONE_H_ + +#include "CenDsrcTollingZoneID.h" +#include "Latitude.h" +#include "Longitude.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CenDsrcTollingZone_SOURCE) +#define CenDsrcTollingZone_DllAPI __declspec( dllexport ) +#else +#define CenDsrcTollingZone_DllAPI __declspec( dllimport ) +#endif // CenDsrcTollingZone_SOURCE +#else +#define CenDsrcTollingZone_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CenDsrcTollingZone_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure CenDsrcTollingZone defined by the user in the IDL file. + * @ingroup CENDSRCTOLLINGZONE + */ + class CenDsrcTollingZone + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CenDsrcTollingZone(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CenDsrcTollingZone(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::CenDsrcTollingZone that will be copied. + */ + eProsima_user_DllExport CenDsrcTollingZone( + const CenDsrcTollingZone& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::CenDsrcTollingZone that will be copied. + */ + eProsima_user_DllExport CenDsrcTollingZone( + CenDsrcTollingZone&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::CenDsrcTollingZone that will be copied. + */ + eProsima_user_DllExport CenDsrcTollingZone& operator =( + const CenDsrcTollingZone& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::CenDsrcTollingZone that will be copied. + */ + eProsima_user_DllExport CenDsrcTollingZone& operator =( + CenDsrcTollingZone&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::CenDsrcTollingZone object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CenDsrcTollingZone& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::CenDsrcTollingZone object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CenDsrcTollingZone& x) const; + + /*! + * @brief This function copies the value in member protected_zone_latitude + * @param _protected_zone_latitude New value to be copied in member protected_zone_latitude + */ + eProsima_user_DllExport void protected_zone_latitude( + const etsi_its_cam_msgs::msg::Latitude& _protected_zone_latitude); + + /*! + * @brief This function moves the value in member protected_zone_latitude + * @param _protected_zone_latitude New value to be moved in member protected_zone_latitude + */ + eProsima_user_DllExport void protected_zone_latitude( + etsi_its_cam_msgs::msg::Latitude&& _protected_zone_latitude); + + /*! + * @brief This function returns a constant reference to member protected_zone_latitude + * @return Constant reference to member protected_zone_latitude + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::Latitude& protected_zone_latitude() const; + + /*! + * @brief This function returns a reference to member protected_zone_latitude + * @return Reference to member protected_zone_latitude + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::Latitude& protected_zone_latitude(); + /*! + * @brief This function copies the value in member protected_zone_longitude + * @param _protected_zone_longitude New value to be copied in member protected_zone_longitude + */ + eProsima_user_DllExport void protected_zone_longitude( + const etsi_its_cam_msgs::msg::Longitude& _protected_zone_longitude); + + /*! + * @brief This function moves the value in member protected_zone_longitude + * @param _protected_zone_longitude New value to be moved in member protected_zone_longitude + */ + eProsima_user_DllExport void protected_zone_longitude( + etsi_its_cam_msgs::msg::Longitude&& _protected_zone_longitude); + + /*! + * @brief This function returns a constant reference to member protected_zone_longitude + * @return Constant reference to member protected_zone_longitude + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::Longitude& protected_zone_longitude() const; + + /*! + * @brief This function returns a reference to member protected_zone_longitude + * @return Reference to member protected_zone_longitude + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::Longitude& protected_zone_longitude(); + /*! + * @brief This function copies the value in member cen_dsrc_tolling_zone_id + * @param _cen_dsrc_tolling_zone_id New value to be copied in member cen_dsrc_tolling_zone_id + */ + eProsima_user_DllExport void cen_dsrc_tolling_zone_id( + const etsi_its_cam_msgs::msg::CenDsrcTollingZoneID& _cen_dsrc_tolling_zone_id); + + /*! + * @brief This function moves the value in member cen_dsrc_tolling_zone_id + * @param _cen_dsrc_tolling_zone_id New value to be moved in member cen_dsrc_tolling_zone_id + */ + eProsima_user_DllExport void cen_dsrc_tolling_zone_id( + etsi_its_cam_msgs::msg::CenDsrcTollingZoneID&& _cen_dsrc_tolling_zone_id); + + /*! + * @brief This function returns a constant reference to member cen_dsrc_tolling_zone_id + * @return Constant reference to member cen_dsrc_tolling_zone_id + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::CenDsrcTollingZoneID& cen_dsrc_tolling_zone_id() const; + + /*! + * @brief This function returns a reference to member cen_dsrc_tolling_zone_id + * @return Reference to member cen_dsrc_tolling_zone_id + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::CenDsrcTollingZoneID& cen_dsrc_tolling_zone_id(); + /*! + * @brief This function sets a value in member cen_dsrc_tolling_zone_id_is_present + * @param _cen_dsrc_tolling_zone_id_is_present New value for member cen_dsrc_tolling_zone_id_is_present + */ + eProsima_user_DllExport void cen_dsrc_tolling_zone_id_is_present( + bool _cen_dsrc_tolling_zone_id_is_present); + + /*! + * @brief This function returns the value of member cen_dsrc_tolling_zone_id_is_present + * @return Value of member cen_dsrc_tolling_zone_id_is_present + */ + eProsima_user_DllExport bool cen_dsrc_tolling_zone_id_is_present() const; + + /*! + * @brief This function returns a reference to member cen_dsrc_tolling_zone_id_is_present + * @return Reference to member cen_dsrc_tolling_zone_id_is_present + */ + eProsima_user_DllExport bool& cen_dsrc_tolling_zone_id_is_present(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::CenDsrcTollingZone& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::Latitude m_protected_zone_latitude; + etsi_its_cam_msgs::msg::Longitude m_protected_zone_longitude; + etsi_its_cam_msgs::msg::CenDsrcTollingZoneID m_cen_dsrc_tolling_zone_id; + bool m_cen_dsrc_tolling_zone_id_is_present; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.cxx new file mode 100644 index 00000000000..ccaaca96dbd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.cxx @@ -0,0 +1,190 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CenDsrcTollingZoneID.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CenDsrcTollingZoneID.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::CenDsrcTollingZoneID() +{ + // m_value com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@415156bf + + +} + +etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::~CenDsrcTollingZoneID() +{ +} + +etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::CenDsrcTollingZoneID( + const CenDsrcTollingZoneID& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::CenDsrcTollingZoneID( + CenDsrcTollingZoneID&& x) +{ + m_value = std::move(x.m_value); +} + +etsi_its_cam_msgs::msg::CenDsrcTollingZoneID& etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::operator =( + const CenDsrcTollingZoneID& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::CenDsrcTollingZoneID& etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::operator =( + CenDsrcTollingZoneID&& x) +{ + + m_value = std::move(x.m_value); + + return *this; +} + +bool etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::operator ==( + const CenDsrcTollingZoneID& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::operator !=( + const CenDsrcTollingZoneID& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::ProtectedZoneID::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::CenDsrcTollingZoneID& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::ProtectedZoneID::getCdrSerializedSize(data.value(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ +void etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::value( + const etsi_its_cam_msgs::msg::ProtectedZoneID& _value) +{ + m_value = _value; +} + +/*! + * @brief This function moves the value in member value + * @param _value New value to be moved in member value + */ +void etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::value( + etsi_its_cam_msgs::msg::ProtectedZoneID&& _value) +{ + m_value = std::move(_value); +} + +/*! + * @brief This function returns a constant reference to member value + * @return Constant reference to member value + */ +const etsi_its_cam_msgs::msg::ProtectedZoneID& etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +etsi_its_cam_msgs::msg::ProtectedZoneID& etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::value() +{ + return m_value; +} + +size_t etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::CenDsrcTollingZoneID::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.h new file mode 100644 index 00000000000..e12abfd73e2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CenDsrcTollingZoneID.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONEID_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONEID_H_ + +#include "ProtectedZoneID.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CenDsrcTollingZoneID_SOURCE) +#define CenDsrcTollingZoneID_DllAPI __declspec( dllexport ) +#else +#define CenDsrcTollingZoneID_DllAPI __declspec( dllimport ) +#endif // CenDsrcTollingZoneID_SOURCE +#else +#define CenDsrcTollingZoneID_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CenDsrcTollingZoneID_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure CenDsrcTollingZoneID defined by the user in the IDL file. + * @ingroup CENDSRCTOLLINGZONEID + */ + class CenDsrcTollingZoneID + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CenDsrcTollingZoneID(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CenDsrcTollingZoneID(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::CenDsrcTollingZoneID that will be copied. + */ + eProsima_user_DllExport CenDsrcTollingZoneID( + const CenDsrcTollingZoneID& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::CenDsrcTollingZoneID that will be copied. + */ + eProsima_user_DllExport CenDsrcTollingZoneID( + CenDsrcTollingZoneID&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::CenDsrcTollingZoneID that will be copied. + */ + eProsima_user_DllExport CenDsrcTollingZoneID& operator =( + const CenDsrcTollingZoneID& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::CenDsrcTollingZoneID that will be copied. + */ + eProsima_user_DllExport CenDsrcTollingZoneID& operator =( + CenDsrcTollingZoneID&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::CenDsrcTollingZoneID object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CenDsrcTollingZoneID& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::CenDsrcTollingZoneID object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CenDsrcTollingZoneID& x) const; + + /*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ + eProsima_user_DllExport void value( + const etsi_its_cam_msgs::msg::ProtectedZoneID& _value); + + /*! + * @brief This function moves the value in member value + * @param _value New value to be moved in member value + */ + eProsima_user_DllExport void value( + etsi_its_cam_msgs::msg::ProtectedZoneID&& _value); + + /*! + * @brief This function returns a constant reference to member value + * @return Constant reference to member value + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::ProtectedZoneID& value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::ProtectedZoneID& value(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::CenDsrcTollingZoneID& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::ProtectedZoneID m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONEID_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneIDPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneIDPubSubTypes.cxx new file mode 100644 index 00000000000..e8ee768751f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneIDPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CenDsrcTollingZoneIDPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CenDsrcTollingZoneIDPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + CenDsrcTollingZoneIDPubSubType::CenDsrcTollingZoneIDPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::CenDsrcTollingZoneID_"); + auto type_size = CenDsrcTollingZoneID::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CenDsrcTollingZoneID::isKeyDefined(); + size_t keyLength = CenDsrcTollingZoneID::getKeyMaxCdrSerializedSize() > 16 ? + CenDsrcTollingZoneID::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CenDsrcTollingZoneIDPubSubType::~CenDsrcTollingZoneIDPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CenDsrcTollingZoneIDPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CenDsrcTollingZoneID* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CenDsrcTollingZoneIDPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CenDsrcTollingZoneID* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CenDsrcTollingZoneIDPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CenDsrcTollingZoneIDPubSubType::createData() + { + return reinterpret_cast(new CenDsrcTollingZoneID()); + } + + void CenDsrcTollingZoneIDPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CenDsrcTollingZoneIDPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CenDsrcTollingZoneID* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CenDsrcTollingZoneID::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CenDsrcTollingZoneID::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneIDPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneIDPubSubTypes.h new file mode 100644 index 00000000000..0344ef1440d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneIDPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CenDsrcTollingZoneIDPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONEID_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONEID_PUBSUBTYPES_H_ + +#include +#include + +#include "CenDsrcTollingZoneID.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CenDsrcTollingZoneID is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CenDsrcTollingZoneID defined by the user in the IDL file. + * @ingroup CENDSRCTOLLINGZONEID + */ + class CenDsrcTollingZoneIDPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CenDsrcTollingZoneID type; + + eProsima_user_DllExport CenDsrcTollingZoneIDPubSubType(); + + eProsima_user_DllExport virtual ~CenDsrcTollingZoneIDPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) CenDsrcTollingZoneID(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONEID_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZonePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZonePubSubTypes.cxx new file mode 100644 index 00000000000..bd71435e5d0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZonePubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CenDsrcTollingZonePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CenDsrcTollingZonePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + CenDsrcTollingZonePubSubType::CenDsrcTollingZonePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::CenDsrcTollingZone_"); + auto type_size = CenDsrcTollingZone::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CenDsrcTollingZone::isKeyDefined(); + size_t keyLength = CenDsrcTollingZone::getKeyMaxCdrSerializedSize() > 16 ? + CenDsrcTollingZone::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CenDsrcTollingZonePubSubType::~CenDsrcTollingZonePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CenDsrcTollingZonePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CenDsrcTollingZone* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CenDsrcTollingZonePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CenDsrcTollingZone* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CenDsrcTollingZonePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CenDsrcTollingZonePubSubType::createData() + { + return reinterpret_cast(new CenDsrcTollingZone()); + } + + void CenDsrcTollingZonePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CenDsrcTollingZonePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CenDsrcTollingZone* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CenDsrcTollingZone::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CenDsrcTollingZone::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZonePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZonePubSubTypes.h new file mode 100644 index 00000000000..30e07101f51 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZonePubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CenDsrcTollingZonePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONE_PUBSUBTYPES_H_ + +#include +#include + +#include "CenDsrcTollingZone.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CenDsrcTollingZone is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type CenDsrcTollingZone defined by the user in the IDL file. + * @ingroup CENDSRCTOLLINGZONE + */ + class CenDsrcTollingZonePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CenDsrcTollingZone type; + + eProsima_user_DllExport CenDsrcTollingZonePubSubType(); + + eProsima_user_DllExport virtual ~CenDsrcTollingZonePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) CenDsrcTollingZone(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanes.cxx new file mode 100644 index 00000000000..25702357b44 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanes.cxx @@ -0,0 +1,415 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ClosedLanes.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "ClosedLanes.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::ClosedLanes::ClosedLanes() +{ + // m_innerhard_shoulder_status com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@841e575 + + // m_innerhard_shoulder_status_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@27a5328c + m_innerhard_shoulder_status_is_present = false; + // m_outerhard_shoulder_status com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@841e575 + + // m_outerhard_shoulder_status_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@1e5f4170 + m_outerhard_shoulder_status_is_present = false; + // m_driving_lane_status com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@6c345c5f + + // m_driving_lane_status_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@6b5966e1 + m_driving_lane_status_is_present = false; + +} + +etsi_its_cam_msgs::msg::ClosedLanes::~ClosedLanes() +{ + + + + + +} + +etsi_its_cam_msgs::msg::ClosedLanes::ClosedLanes( + const ClosedLanes& x) +{ + m_innerhard_shoulder_status = x.m_innerhard_shoulder_status; + m_innerhard_shoulder_status_is_present = x.m_innerhard_shoulder_status_is_present; + m_outerhard_shoulder_status = x.m_outerhard_shoulder_status; + m_outerhard_shoulder_status_is_present = x.m_outerhard_shoulder_status_is_present; + m_driving_lane_status = x.m_driving_lane_status; + m_driving_lane_status_is_present = x.m_driving_lane_status_is_present; +} + +etsi_its_cam_msgs::msg::ClosedLanes::ClosedLanes( + ClosedLanes&& x) +{ + m_innerhard_shoulder_status = std::move(x.m_innerhard_shoulder_status); + m_innerhard_shoulder_status_is_present = x.m_innerhard_shoulder_status_is_present; + m_outerhard_shoulder_status = std::move(x.m_outerhard_shoulder_status); + m_outerhard_shoulder_status_is_present = x.m_outerhard_shoulder_status_is_present; + m_driving_lane_status = std::move(x.m_driving_lane_status); + m_driving_lane_status_is_present = x.m_driving_lane_status_is_present; +} + +etsi_its_cam_msgs::msg::ClosedLanes& etsi_its_cam_msgs::msg::ClosedLanes::operator =( + const ClosedLanes& x) +{ + + m_innerhard_shoulder_status = x.m_innerhard_shoulder_status; + m_innerhard_shoulder_status_is_present = x.m_innerhard_shoulder_status_is_present; + m_outerhard_shoulder_status = x.m_outerhard_shoulder_status; + m_outerhard_shoulder_status_is_present = x.m_outerhard_shoulder_status_is_present; + m_driving_lane_status = x.m_driving_lane_status; + m_driving_lane_status_is_present = x.m_driving_lane_status_is_present; + + return *this; +} + +etsi_its_cam_msgs::msg::ClosedLanes& etsi_its_cam_msgs::msg::ClosedLanes::operator =( + ClosedLanes&& x) +{ + + m_innerhard_shoulder_status = std::move(x.m_innerhard_shoulder_status); + m_innerhard_shoulder_status_is_present = x.m_innerhard_shoulder_status_is_present; + m_outerhard_shoulder_status = std::move(x.m_outerhard_shoulder_status); + m_outerhard_shoulder_status_is_present = x.m_outerhard_shoulder_status_is_present; + m_driving_lane_status = std::move(x.m_driving_lane_status); + m_driving_lane_status_is_present = x.m_driving_lane_status_is_present; + + return *this; +} + +bool etsi_its_cam_msgs::msg::ClosedLanes::operator ==( + const ClosedLanes& x) const +{ + + return (m_innerhard_shoulder_status == x.m_innerhard_shoulder_status && m_innerhard_shoulder_status_is_present == x.m_innerhard_shoulder_status_is_present && m_outerhard_shoulder_status == x.m_outerhard_shoulder_status && m_outerhard_shoulder_status_is_present == x.m_outerhard_shoulder_status_is_present && m_driving_lane_status == x.m_driving_lane_status && m_driving_lane_status_is_present == x.m_driving_lane_status_is_present); +} + +bool etsi_its_cam_msgs::msg::ClosedLanes::operator !=( + const ClosedLanes& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::ClosedLanes::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::HardShoulderStatus::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::HardShoulderStatus::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::DrivingLaneStatus::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::ClosedLanes::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::ClosedLanes& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::HardShoulderStatus::getCdrSerializedSize(data.innerhard_shoulder_status(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::HardShoulderStatus::getCdrSerializedSize(data.outerhard_shoulder_status(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::DrivingLaneStatus::getCdrSerializedSize(data.driving_lane_status(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::ClosedLanes::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_innerhard_shoulder_status; + scdr << m_innerhard_shoulder_status_is_present; + scdr << m_outerhard_shoulder_status; + scdr << m_outerhard_shoulder_status_is_present; + scdr << m_driving_lane_status; + scdr << m_driving_lane_status_is_present; + +} + +void etsi_its_cam_msgs::msg::ClosedLanes::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_innerhard_shoulder_status; + dcdr >> m_innerhard_shoulder_status_is_present; + dcdr >> m_outerhard_shoulder_status; + dcdr >> m_outerhard_shoulder_status_is_present; + dcdr >> m_driving_lane_status; + dcdr >> m_driving_lane_status_is_present; +} + +/*! + * @brief This function copies the value in member innerhard_shoulder_status + * @param _innerhard_shoulder_status New value to be copied in member innerhard_shoulder_status + */ +void etsi_its_cam_msgs::msg::ClosedLanes::innerhard_shoulder_status( + const etsi_its_cam_msgs::msg::HardShoulderStatus& _innerhard_shoulder_status) +{ + m_innerhard_shoulder_status = _innerhard_shoulder_status; +} + +/*! + * @brief This function moves the value in member innerhard_shoulder_status + * @param _innerhard_shoulder_status New value to be moved in member innerhard_shoulder_status + */ +void etsi_its_cam_msgs::msg::ClosedLanes::innerhard_shoulder_status( + etsi_its_cam_msgs::msg::HardShoulderStatus&& _innerhard_shoulder_status) +{ + m_innerhard_shoulder_status = std::move(_innerhard_shoulder_status); +} + +/*! + * @brief This function returns a constant reference to member innerhard_shoulder_status + * @return Constant reference to member innerhard_shoulder_status + */ +const etsi_its_cam_msgs::msg::HardShoulderStatus& etsi_its_cam_msgs::msg::ClosedLanes::innerhard_shoulder_status() const +{ + return m_innerhard_shoulder_status; +} + +/*! + * @brief This function returns a reference to member innerhard_shoulder_status + * @return Reference to member innerhard_shoulder_status + */ +etsi_its_cam_msgs::msg::HardShoulderStatus& etsi_its_cam_msgs::msg::ClosedLanes::innerhard_shoulder_status() +{ + return m_innerhard_shoulder_status; +} +/*! + * @brief This function sets a value in member innerhard_shoulder_status_is_present + * @param _innerhard_shoulder_status_is_present New value for member innerhard_shoulder_status_is_present + */ +void etsi_its_cam_msgs::msg::ClosedLanes::innerhard_shoulder_status_is_present( + bool _innerhard_shoulder_status_is_present) +{ + m_innerhard_shoulder_status_is_present = _innerhard_shoulder_status_is_present; +} + +/*! + * @brief This function returns the value of member innerhard_shoulder_status_is_present + * @return Value of member innerhard_shoulder_status_is_present + */ +bool etsi_its_cam_msgs::msg::ClosedLanes::innerhard_shoulder_status_is_present() const +{ + return m_innerhard_shoulder_status_is_present; +} + +/*! + * @brief This function returns a reference to member innerhard_shoulder_status_is_present + * @return Reference to member innerhard_shoulder_status_is_present + */ +bool& etsi_its_cam_msgs::msg::ClosedLanes::innerhard_shoulder_status_is_present() +{ + return m_innerhard_shoulder_status_is_present; +} + +/*! + * @brief This function copies the value in member outerhard_shoulder_status + * @param _outerhard_shoulder_status New value to be copied in member outerhard_shoulder_status + */ +void etsi_its_cam_msgs::msg::ClosedLanes::outerhard_shoulder_status( + const etsi_its_cam_msgs::msg::HardShoulderStatus& _outerhard_shoulder_status) +{ + m_outerhard_shoulder_status = _outerhard_shoulder_status; +} + +/*! + * @brief This function moves the value in member outerhard_shoulder_status + * @param _outerhard_shoulder_status New value to be moved in member outerhard_shoulder_status + */ +void etsi_its_cam_msgs::msg::ClosedLanes::outerhard_shoulder_status( + etsi_its_cam_msgs::msg::HardShoulderStatus&& _outerhard_shoulder_status) +{ + m_outerhard_shoulder_status = std::move(_outerhard_shoulder_status); +} + +/*! + * @brief This function returns a constant reference to member outerhard_shoulder_status + * @return Constant reference to member outerhard_shoulder_status + */ +const etsi_its_cam_msgs::msg::HardShoulderStatus& etsi_its_cam_msgs::msg::ClosedLanes::outerhard_shoulder_status() const +{ + return m_outerhard_shoulder_status; +} + +/*! + * @brief This function returns a reference to member outerhard_shoulder_status + * @return Reference to member outerhard_shoulder_status + */ +etsi_its_cam_msgs::msg::HardShoulderStatus& etsi_its_cam_msgs::msg::ClosedLanes::outerhard_shoulder_status() +{ + return m_outerhard_shoulder_status; +} +/*! + * @brief This function sets a value in member outerhard_shoulder_status_is_present + * @param _outerhard_shoulder_status_is_present New value for member outerhard_shoulder_status_is_present + */ +void etsi_its_cam_msgs::msg::ClosedLanes::outerhard_shoulder_status_is_present( + bool _outerhard_shoulder_status_is_present) +{ + m_outerhard_shoulder_status_is_present = _outerhard_shoulder_status_is_present; +} + +/*! + * @brief This function returns the value of member outerhard_shoulder_status_is_present + * @return Value of member outerhard_shoulder_status_is_present + */ +bool etsi_its_cam_msgs::msg::ClosedLanes::outerhard_shoulder_status_is_present() const +{ + return m_outerhard_shoulder_status_is_present; +} + +/*! + * @brief This function returns a reference to member outerhard_shoulder_status_is_present + * @return Reference to member outerhard_shoulder_status_is_present + */ +bool& etsi_its_cam_msgs::msg::ClosedLanes::outerhard_shoulder_status_is_present() +{ + return m_outerhard_shoulder_status_is_present; +} + +/*! + * @brief This function copies the value in member driving_lane_status + * @param _driving_lane_status New value to be copied in member driving_lane_status + */ +void etsi_its_cam_msgs::msg::ClosedLanes::driving_lane_status( + const etsi_its_cam_msgs::msg::DrivingLaneStatus& _driving_lane_status) +{ + m_driving_lane_status = _driving_lane_status; +} + +/*! + * @brief This function moves the value in member driving_lane_status + * @param _driving_lane_status New value to be moved in member driving_lane_status + */ +void etsi_its_cam_msgs::msg::ClosedLanes::driving_lane_status( + etsi_its_cam_msgs::msg::DrivingLaneStatus&& _driving_lane_status) +{ + m_driving_lane_status = std::move(_driving_lane_status); +} + +/*! + * @brief This function returns a constant reference to member driving_lane_status + * @return Constant reference to member driving_lane_status + */ +const etsi_its_cam_msgs::msg::DrivingLaneStatus& etsi_its_cam_msgs::msg::ClosedLanes::driving_lane_status() const +{ + return m_driving_lane_status; +} + +/*! + * @brief This function returns a reference to member driving_lane_status + * @return Reference to member driving_lane_status + */ +etsi_its_cam_msgs::msg::DrivingLaneStatus& etsi_its_cam_msgs::msg::ClosedLanes::driving_lane_status() +{ + return m_driving_lane_status; +} +/*! + * @brief This function sets a value in member driving_lane_status_is_present + * @param _driving_lane_status_is_present New value for member driving_lane_status_is_present + */ +void etsi_its_cam_msgs::msg::ClosedLanes::driving_lane_status_is_present( + bool _driving_lane_status_is_present) +{ + m_driving_lane_status_is_present = _driving_lane_status_is_present; +} + +/*! + * @brief This function returns the value of member driving_lane_status_is_present + * @return Value of member driving_lane_status_is_present + */ +bool etsi_its_cam_msgs::msg::ClosedLanes::driving_lane_status_is_present() const +{ + return m_driving_lane_status_is_present; +} + +/*! + * @brief This function returns a reference to member driving_lane_status_is_present + * @return Reference to member driving_lane_status_is_present + */ +bool& etsi_its_cam_msgs::msg::ClosedLanes::driving_lane_status_is_present() +{ + return m_driving_lane_status_is_present; +} + + +size_t etsi_its_cam_msgs::msg::ClosedLanes::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::ClosedLanes::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::ClosedLanes::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanes.h new file mode 100644 index 00000000000..5695fa93c41 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanes.h @@ -0,0 +1,330 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ClosedLanes.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CLOSEDLANES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CLOSEDLANES_H_ + +#include "HardShoulderStatus.h" +#include "DrivingLaneStatus.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(ClosedLanes_SOURCE) +#define ClosedLanes_DllAPI __declspec( dllexport ) +#else +#define ClosedLanes_DllAPI __declspec( dllimport ) +#endif // ClosedLanes_SOURCE +#else +#define ClosedLanes_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define ClosedLanes_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure ClosedLanes defined by the user in the IDL file. + * @ingroup CLOSEDLANES + */ + class ClosedLanes + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport ClosedLanes(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~ClosedLanes(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::ClosedLanes that will be copied. + */ + eProsima_user_DllExport ClosedLanes( + const ClosedLanes& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::ClosedLanes that will be copied. + */ + eProsima_user_DllExport ClosedLanes( + ClosedLanes&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::ClosedLanes that will be copied. + */ + eProsima_user_DllExport ClosedLanes& operator =( + const ClosedLanes& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::ClosedLanes that will be copied. + */ + eProsima_user_DllExport ClosedLanes& operator =( + ClosedLanes&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::ClosedLanes object to compare. + */ + eProsima_user_DllExport bool operator ==( + const ClosedLanes& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::ClosedLanes object to compare. + */ + eProsima_user_DllExport bool operator !=( + const ClosedLanes& x) const; + + /*! + * @brief This function copies the value in member innerhard_shoulder_status + * @param _innerhard_shoulder_status New value to be copied in member innerhard_shoulder_status + */ + eProsima_user_DllExport void innerhard_shoulder_status( + const etsi_its_cam_msgs::msg::HardShoulderStatus& _innerhard_shoulder_status); + + /*! + * @brief This function moves the value in member innerhard_shoulder_status + * @param _innerhard_shoulder_status New value to be moved in member innerhard_shoulder_status + */ + eProsima_user_DllExport void innerhard_shoulder_status( + etsi_its_cam_msgs::msg::HardShoulderStatus&& _innerhard_shoulder_status); + + /*! + * @brief This function returns a constant reference to member innerhard_shoulder_status + * @return Constant reference to member innerhard_shoulder_status + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::HardShoulderStatus& innerhard_shoulder_status() const; + + /*! + * @brief This function returns a reference to member innerhard_shoulder_status + * @return Reference to member innerhard_shoulder_status + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::HardShoulderStatus& innerhard_shoulder_status(); + /*! + * @brief This function sets a value in member innerhard_shoulder_status_is_present + * @param _innerhard_shoulder_status_is_present New value for member innerhard_shoulder_status_is_present + */ + eProsima_user_DllExport void innerhard_shoulder_status_is_present( + bool _innerhard_shoulder_status_is_present); + + /*! + * @brief This function returns the value of member innerhard_shoulder_status_is_present + * @return Value of member innerhard_shoulder_status_is_present + */ + eProsima_user_DllExport bool innerhard_shoulder_status_is_present() const; + + /*! + * @brief This function returns a reference to member innerhard_shoulder_status_is_present + * @return Reference to member innerhard_shoulder_status_is_present + */ + eProsima_user_DllExport bool& innerhard_shoulder_status_is_present(); + + /*! + * @brief This function copies the value in member outerhard_shoulder_status + * @param _outerhard_shoulder_status New value to be copied in member outerhard_shoulder_status + */ + eProsima_user_DllExport void outerhard_shoulder_status( + const etsi_its_cam_msgs::msg::HardShoulderStatus& _outerhard_shoulder_status); + + /*! + * @brief This function moves the value in member outerhard_shoulder_status + * @param _outerhard_shoulder_status New value to be moved in member outerhard_shoulder_status + */ + eProsima_user_DllExport void outerhard_shoulder_status( + etsi_its_cam_msgs::msg::HardShoulderStatus&& _outerhard_shoulder_status); + + /*! + * @brief This function returns a constant reference to member outerhard_shoulder_status + * @return Constant reference to member outerhard_shoulder_status + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::HardShoulderStatus& outerhard_shoulder_status() const; + + /*! + * @brief This function returns a reference to member outerhard_shoulder_status + * @return Reference to member outerhard_shoulder_status + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::HardShoulderStatus& outerhard_shoulder_status(); + /*! + * @brief This function sets a value in member outerhard_shoulder_status_is_present + * @param _outerhard_shoulder_status_is_present New value for member outerhard_shoulder_status_is_present + */ + eProsima_user_DllExport void outerhard_shoulder_status_is_present( + bool _outerhard_shoulder_status_is_present); + + /*! + * @brief This function returns the value of member outerhard_shoulder_status_is_present + * @return Value of member outerhard_shoulder_status_is_present + */ + eProsima_user_DllExport bool outerhard_shoulder_status_is_present() const; + + /*! + * @brief This function returns a reference to member outerhard_shoulder_status_is_present + * @return Reference to member outerhard_shoulder_status_is_present + */ + eProsima_user_DllExport bool& outerhard_shoulder_status_is_present(); + + /*! + * @brief This function copies the value in member driving_lane_status + * @param _driving_lane_status New value to be copied in member driving_lane_status + */ + eProsima_user_DllExport void driving_lane_status( + const etsi_its_cam_msgs::msg::DrivingLaneStatus& _driving_lane_status); + + /*! + * @brief This function moves the value in member driving_lane_status + * @param _driving_lane_status New value to be moved in member driving_lane_status + */ + eProsima_user_DllExport void driving_lane_status( + etsi_its_cam_msgs::msg::DrivingLaneStatus&& _driving_lane_status); + + /*! + * @brief This function returns a constant reference to member driving_lane_status + * @return Constant reference to member driving_lane_status + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::DrivingLaneStatus& driving_lane_status() const; + + /*! + * @brief This function returns a reference to member driving_lane_status + * @return Reference to member driving_lane_status + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::DrivingLaneStatus& driving_lane_status(); + /*! + * @brief This function sets a value in member driving_lane_status_is_present + * @param _driving_lane_status_is_present New value for member driving_lane_status_is_present + */ + eProsima_user_DllExport void driving_lane_status_is_present( + bool _driving_lane_status_is_present); + + /*! + * @brief This function returns the value of member driving_lane_status_is_present + * @return Value of member driving_lane_status_is_present + */ + eProsima_user_DllExport bool driving_lane_status_is_present() const; + + /*! + * @brief This function returns a reference to member driving_lane_status_is_present + * @return Reference to member driving_lane_status_is_present + */ + eProsima_user_DllExport bool& driving_lane_status_is_present(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::ClosedLanes& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::HardShoulderStatus m_innerhard_shoulder_status; + bool m_innerhard_shoulder_status_is_present; + etsi_its_cam_msgs::msg::HardShoulderStatus m_outerhard_shoulder_status; + bool m_outerhard_shoulder_status_is_present; + etsi_its_cam_msgs::msg::DrivingLaneStatus m_driving_lane_status; + bool m_driving_lane_status_is_present; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CLOSEDLANES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanesPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanesPubSubTypes.cxx new file mode 100644 index 00000000000..e9942e6527e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanesPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ClosedLanesPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "ClosedLanesPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + ClosedLanesPubSubType::ClosedLanesPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::ClosedLanes_"); + auto type_size = ClosedLanes::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = ClosedLanes::isKeyDefined(); + size_t keyLength = ClosedLanes::getKeyMaxCdrSerializedSize() > 16 ? + ClosedLanes::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + ClosedLanesPubSubType::~ClosedLanesPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool ClosedLanesPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + ClosedLanes* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool ClosedLanesPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + ClosedLanes* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function ClosedLanesPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* ClosedLanesPubSubType::createData() + { + return reinterpret_cast(new ClosedLanes()); + } + + void ClosedLanesPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool ClosedLanesPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + ClosedLanes* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + ClosedLanes::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || ClosedLanes::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/types/PointCloud2PubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanesPubSubTypes.h similarity index 79% rename from LibCarla/source/carla/ros2/types/PointCloud2PubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanesPubSubTypes.h index 3fe6150ed01..688689788fe 100644 --- a/LibCarla/source/carla/ros2/types/PointCloud2PubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanesPubSubTypes.h @@ -13,46 +13,43 @@ // limitations under the License. /*! - * @file PointCloud2PubSubTypes.h + * @file ClosedLanesPubSubTypes.h * This header file contains the declaration of the serialization functions. * * This file was generated by the tool fastcdrgen. */ -#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2_PUBSUBTYPES_H_ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CLOSEDLANES_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CLOSEDLANES_PUBSUBTYPES_H_ #include #include -#include "PointCloud2.h" - -#include "HeaderPubSubTypes.h" -#include "PointFieldPubSubTypes.h" +#include "ClosedLanes.h" #if !defined(GEN_API_VER) || (GEN_API_VER != 1) #error \ - Generated PointCloud2 is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. + Generated ClosedLanes is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. #endif // GEN_API_VER -namespace sensor_msgs +namespace etsi_its_cam_msgs { namespace msg { - /*! - * @brief This class represents the TopicDataType of the type PointCloud2 defined by the user in the IDL file. - * @ingroup POINTCLOUD2 + * @brief This class represents the TopicDataType of the type ClosedLanes defined by the user in the IDL file. + * @ingroup CLOSEDLANES */ - class PointCloud2PubSubType : public eprosima::fastdds::dds::TopicDataType + class ClosedLanesPubSubType : public eprosima::fastdds::dds::TopicDataType { public: - typedef PointCloud2 type; + typedef ClosedLanes type; - eProsima_user_DllExport PointCloud2PubSubType(); + eProsima_user_DllExport ClosedLanesPubSubType(); - eProsima_user_DllExport virtual ~PointCloud2PubSubType() override; + eProsima_user_DllExport virtual ~ClosedLanesPubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -100,10 +97,11 @@ namespace sensor_msgs } #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; unsigned char* m_keyBuffer; }; } } -#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CLOSEDLANES_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwareness.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwareness.cxx new file mode 100644 index 00000000000..27559cd96df --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwareness.cxx @@ -0,0 +1,238 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CoopAwareness.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CoopAwareness.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::CoopAwareness::CoopAwareness() +{ + // m_generation_delta_time com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@29e6eb25 + + // m_cam_parameters com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@62435e70 + + +} + +etsi_its_cam_msgs::msg::CoopAwareness::~CoopAwareness() +{ + +} + +etsi_its_cam_msgs::msg::CoopAwareness::CoopAwareness( + const CoopAwareness& x) +{ + m_generation_delta_time = x.m_generation_delta_time; + m_cam_parameters = x.m_cam_parameters; +} + +etsi_its_cam_msgs::msg::CoopAwareness::CoopAwareness( + CoopAwareness&& x) +{ + m_generation_delta_time = std::move(x.m_generation_delta_time); + m_cam_parameters = std::move(x.m_cam_parameters); +} + +etsi_its_cam_msgs::msg::CoopAwareness& etsi_its_cam_msgs::msg::CoopAwareness::operator =( + const CoopAwareness& x) +{ + + m_generation_delta_time = x.m_generation_delta_time; + m_cam_parameters = x.m_cam_parameters; + + return *this; +} + +etsi_its_cam_msgs::msg::CoopAwareness& etsi_its_cam_msgs::msg::CoopAwareness::operator =( + CoopAwareness&& x) +{ + + m_generation_delta_time = std::move(x.m_generation_delta_time); + m_cam_parameters = std::move(x.m_cam_parameters); + + return *this; +} + +bool etsi_its_cam_msgs::msg::CoopAwareness::operator ==( + const CoopAwareness& x) const +{ + + return (m_generation_delta_time == x.m_generation_delta_time && m_cam_parameters == x.m_cam_parameters); +} + +bool etsi_its_cam_msgs::msg::CoopAwareness::operator !=( + const CoopAwareness& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::CoopAwareness::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::GenerationDeltaTime::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::CamParameters::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::CoopAwareness::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::CoopAwareness& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::GenerationDeltaTime::getCdrSerializedSize(data.generation_delta_time(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::CamParameters::getCdrSerializedSize(data.cam_parameters(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::CoopAwareness::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_generation_delta_time; + scdr << m_cam_parameters; + +} + +void etsi_its_cam_msgs::msg::CoopAwareness::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_generation_delta_time; + dcdr >> m_cam_parameters; +} + +/*! + * @brief This function copies the value in member generation_delta_time + * @param _generation_delta_time New value to be copied in member generation_delta_time + */ +void etsi_its_cam_msgs::msg::CoopAwareness::generation_delta_time( + const etsi_its_cam_msgs::msg::GenerationDeltaTime& _generation_delta_time) +{ + m_generation_delta_time = _generation_delta_time; +} + +/*! + * @brief This function moves the value in member generation_delta_time + * @param _generation_delta_time New value to be moved in member generation_delta_time + */ +void etsi_its_cam_msgs::msg::CoopAwareness::generation_delta_time( + etsi_its_cam_msgs::msg::GenerationDeltaTime&& _generation_delta_time) +{ + m_generation_delta_time = std::move(_generation_delta_time); +} + +/*! + * @brief This function returns a constant reference to member generation_delta_time + * @return Constant reference to member generation_delta_time + */ +const etsi_its_cam_msgs::msg::GenerationDeltaTime& etsi_its_cam_msgs::msg::CoopAwareness::generation_delta_time() const +{ + return m_generation_delta_time; +} + +/*! + * @brief This function returns a reference to member generation_delta_time + * @return Reference to member generation_delta_time + */ +etsi_its_cam_msgs::msg::GenerationDeltaTime& etsi_its_cam_msgs::msg::CoopAwareness::generation_delta_time() +{ + return m_generation_delta_time; +} +/*! + * @brief This function copies the value in member cam_parameters + * @param _cam_parameters New value to be copied in member cam_parameters + */ +void etsi_its_cam_msgs::msg::CoopAwareness::cam_parameters( + const etsi_its_cam_msgs::msg::CamParameters& _cam_parameters) +{ + m_cam_parameters = _cam_parameters; +} + +/*! + * @brief This function moves the value in member cam_parameters + * @param _cam_parameters New value to be moved in member cam_parameters + */ +void etsi_its_cam_msgs::msg::CoopAwareness::cam_parameters( + etsi_its_cam_msgs::msg::CamParameters&& _cam_parameters) +{ + m_cam_parameters = std::move(_cam_parameters); +} + +/*! + * @brief This function returns a constant reference to member cam_parameters + * @return Constant reference to member cam_parameters + */ +const etsi_its_cam_msgs::msg::CamParameters& etsi_its_cam_msgs::msg::CoopAwareness::cam_parameters() const +{ + return m_cam_parameters; +} + +/*! + * @brief This function returns a reference to member cam_parameters + * @return Reference to member cam_parameters + */ +etsi_its_cam_msgs::msg::CamParameters& etsi_its_cam_msgs::msg::CoopAwareness::cam_parameters() +{ + return m_cam_parameters; +} + +size_t etsi_its_cam_msgs::msg::CoopAwareness::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::CoopAwareness::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::CoopAwareness::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwareness.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwareness.h new file mode 100644 index 00000000000..4b2bd951271 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwareness.h @@ -0,0 +1,244 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CoopAwareness.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_COOPAWARENESS_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_COOPAWARENESS_H_ + +#include "GenerationDeltaTime.h" +#include "CamParameters.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CoopAwareness_SOURCE) +#define CoopAwareness_DllAPI __declspec( dllexport ) +#else +#define CoopAwareness_DllAPI __declspec( dllimport ) +#endif // CoopAwareness_SOURCE +#else +#define CoopAwareness_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CoopAwareness_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure CoopAwareness defined by the user in the IDL file. + * @ingroup COOPAWARENESS + */ + class CoopAwareness + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CoopAwareness(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CoopAwareness(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::CoopAwareness that will be copied. + */ + eProsima_user_DllExport CoopAwareness( + const CoopAwareness& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::CoopAwareness that will be copied. + */ + eProsima_user_DllExport CoopAwareness( + CoopAwareness&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::CoopAwareness that will be copied. + */ + eProsima_user_DllExport CoopAwareness& operator =( + const CoopAwareness& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::CoopAwareness that will be copied. + */ + eProsima_user_DllExport CoopAwareness& operator =( + CoopAwareness&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::CoopAwareness object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CoopAwareness& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::CoopAwareness object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CoopAwareness& x) const; + + /*! + * @brief This function copies the value in member generation_delta_time + * @param _generation_delta_time New value to be copied in member generation_delta_time + */ + eProsima_user_DllExport void generation_delta_time( + const etsi_its_cam_msgs::msg::GenerationDeltaTime& _generation_delta_time); + + /*! + * @brief This function moves the value in member generation_delta_time + * @param _generation_delta_time New value to be moved in member generation_delta_time + */ + eProsima_user_DllExport void generation_delta_time( + etsi_its_cam_msgs::msg::GenerationDeltaTime&& _generation_delta_time); + + /*! + * @brief This function returns a constant reference to member generation_delta_time + * @return Constant reference to member generation_delta_time + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::GenerationDeltaTime& generation_delta_time() const; + + /*! + * @brief This function returns a reference to member generation_delta_time + * @return Reference to member generation_delta_time + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::GenerationDeltaTime& generation_delta_time(); + /*! + * @brief This function copies the value in member cam_parameters + * @param _cam_parameters New value to be copied in member cam_parameters + */ + eProsima_user_DllExport void cam_parameters( + const etsi_its_cam_msgs::msg::CamParameters& _cam_parameters); + + /*! + * @brief This function moves the value in member cam_parameters + * @param _cam_parameters New value to be moved in member cam_parameters + */ + eProsima_user_DllExport void cam_parameters( + etsi_its_cam_msgs::msg::CamParameters&& _cam_parameters); + + /*! + * @brief This function returns a constant reference to member cam_parameters + * @return Constant reference to member cam_parameters + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::CamParameters& cam_parameters() const; + + /*! + * @brief This function returns a reference to member cam_parameters + * @return Reference to member cam_parameters + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::CamParameters& cam_parameters(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::CoopAwareness& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::GenerationDeltaTime m_generation_delta_time; + etsi_its_cam_msgs::msg::CamParameters m_cam_parameters; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_COOPAWARENESS_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwarenessPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwarenessPubSubTypes.cxx new file mode 100644 index 00000000000..8a736799ff5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwarenessPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CoopAwarenessPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CoopAwarenessPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + CoopAwarenessPubSubType::CoopAwarenessPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::CoopAwareness_"); + auto type_size = CoopAwareness::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CoopAwareness::isKeyDefined(); + size_t keyLength = CoopAwareness::getKeyMaxCdrSerializedSize() > 16 ? + CoopAwareness::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CoopAwarenessPubSubType::~CoopAwarenessPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CoopAwarenessPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CoopAwareness* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CoopAwarenessPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CoopAwareness* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CoopAwarenessPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CoopAwarenessPubSubType::createData() + { + return reinterpret_cast(new CoopAwareness()); + } + + void CoopAwarenessPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CoopAwarenessPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CoopAwareness* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CoopAwareness::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CoopAwareness::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/types/HeaderPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwarenessPubSubTypes.h similarity index 78% rename from LibCarla/source/carla/ros2/types/HeaderPubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwarenessPubSubTypes.h index ddc9ca2b87c..d7144b56675 100644 --- a/LibCarla/source/carla/ros2/types/HeaderPubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwarenessPubSubTypes.h @@ -13,42 +13,43 @@ // limitations under the License. /*! - * @file HeaderPubSubTypes.h + * @file CoopAwarenessPubSubTypes.h * This header file contains the declaration of the serialization functions. * * This file was generated by the tool fastcdrgen. */ -#ifndef _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADER_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADER_PUBSUBTYPES_H_ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_COOPAWARENESS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_COOPAWARENESS_PUBSUBTYPES_H_ #include #include -#include "Header.h" +#include "CoopAwareness.h" #if !defined(GEN_API_VER) || (GEN_API_VER != 1) #error \ - Generated Header is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. + Generated CoopAwareness is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. #endif // GEN_API_VER -namespace std_msgs +namespace etsi_its_cam_msgs { namespace msg { /*! - * @brief This class represents the TopicDataType of the type Header defined by the user in the IDL file. - * @ingroup HEADER + * @brief This class represents the TopicDataType of the type CoopAwareness defined by the user in the IDL file. + * @ingroup COOPAWARENESS */ - class HeaderPubSubType : public eprosima::fastdds::dds::TopicDataType + class CoopAwarenessPubSubType : public eprosima::fastdds::dds::TopicDataType { public: - typedef Header type; + typedef CoopAwareness type; - eProsima_user_DllExport HeaderPubSubType(); + eProsima_user_DllExport CoopAwarenessPubSubType(); - eProsima_user_DllExport virtual ~HeaderPubSubType() override; + eProsima_user_DllExport virtual ~CoopAwarenessPubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -103,4 +104,4 @@ namespace std_msgs } } -#endif // _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADER_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_COOPAWARENESS_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Curvature.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Curvature.cxx new file mode 100644 index 00000000000..292a12a8223 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Curvature.cxx @@ -0,0 +1,238 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Curvature.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Curvature.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::Curvature::Curvature() +{ + // m_curvature_value com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@5aae8eb5 + + // m_curvature_confidence com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@76954a33 + + +} + +etsi_its_cam_msgs::msg::Curvature::~Curvature() +{ + +} + +etsi_its_cam_msgs::msg::Curvature::Curvature( + const Curvature& x) +{ + m_curvature_value = x.m_curvature_value; + m_curvature_confidence = x.m_curvature_confidence; +} + +etsi_its_cam_msgs::msg::Curvature::Curvature( + Curvature&& x) +{ + m_curvature_value = std::move(x.m_curvature_value); + m_curvature_confidence = std::move(x.m_curvature_confidence); +} + +etsi_its_cam_msgs::msg::Curvature& etsi_its_cam_msgs::msg::Curvature::operator =( + const Curvature& x) +{ + + m_curvature_value = x.m_curvature_value; + m_curvature_confidence = x.m_curvature_confidence; + + return *this; +} + +etsi_its_cam_msgs::msg::Curvature& etsi_its_cam_msgs::msg::Curvature::operator =( + Curvature&& x) +{ + + m_curvature_value = std::move(x.m_curvature_value); + m_curvature_confidence = std::move(x.m_curvature_confidence); + + return *this; +} + +bool etsi_its_cam_msgs::msg::Curvature::operator ==( + const Curvature& x) const +{ + + return (m_curvature_value == x.m_curvature_value && m_curvature_confidence == x.m_curvature_confidence); +} + +bool etsi_its_cam_msgs::msg::Curvature::operator !=( + const Curvature& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::Curvature::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::CurvatureValue::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::CurvatureConfidence::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::Curvature::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::Curvature& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::CurvatureValue::getCdrSerializedSize(data.curvature_value(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::CurvatureConfidence::getCdrSerializedSize(data.curvature_confidence(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::Curvature::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_curvature_value; + scdr << m_curvature_confidence; + +} + +void etsi_its_cam_msgs::msg::Curvature::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_curvature_value; + dcdr >> m_curvature_confidence; +} + +/*! + * @brief This function copies the value in member curvature_value + * @param _curvature_value New value to be copied in member curvature_value + */ +void etsi_its_cam_msgs::msg::Curvature::curvature_value( + const etsi_its_cam_msgs::msg::CurvatureValue& _curvature_value) +{ + m_curvature_value = _curvature_value; +} + +/*! + * @brief This function moves the value in member curvature_value + * @param _curvature_value New value to be moved in member curvature_value + */ +void etsi_its_cam_msgs::msg::Curvature::curvature_value( + etsi_its_cam_msgs::msg::CurvatureValue&& _curvature_value) +{ + m_curvature_value = std::move(_curvature_value); +} + +/*! + * @brief This function returns a constant reference to member curvature_value + * @return Constant reference to member curvature_value + */ +const etsi_its_cam_msgs::msg::CurvatureValue& etsi_its_cam_msgs::msg::Curvature::curvature_value() const +{ + return m_curvature_value; +} + +/*! + * @brief This function returns a reference to member curvature_value + * @return Reference to member curvature_value + */ +etsi_its_cam_msgs::msg::CurvatureValue& etsi_its_cam_msgs::msg::Curvature::curvature_value() +{ + return m_curvature_value; +} +/*! + * @brief This function copies the value in member curvature_confidence + * @param _curvature_confidence New value to be copied in member curvature_confidence + */ +void etsi_its_cam_msgs::msg::Curvature::curvature_confidence( + const etsi_its_cam_msgs::msg::CurvatureConfidence& _curvature_confidence) +{ + m_curvature_confidence = _curvature_confidence; +} + +/*! + * @brief This function moves the value in member curvature_confidence + * @param _curvature_confidence New value to be moved in member curvature_confidence + */ +void etsi_its_cam_msgs::msg::Curvature::curvature_confidence( + etsi_its_cam_msgs::msg::CurvatureConfidence&& _curvature_confidence) +{ + m_curvature_confidence = std::move(_curvature_confidence); +} + +/*! + * @brief This function returns a constant reference to member curvature_confidence + * @return Constant reference to member curvature_confidence + */ +const etsi_its_cam_msgs::msg::CurvatureConfidence& etsi_its_cam_msgs::msg::Curvature::curvature_confidence() const +{ + return m_curvature_confidence; +} + +/*! + * @brief This function returns a reference to member curvature_confidence + * @return Reference to member curvature_confidence + */ +etsi_its_cam_msgs::msg::CurvatureConfidence& etsi_its_cam_msgs::msg::Curvature::curvature_confidence() +{ + return m_curvature_confidence; +} + +size_t etsi_its_cam_msgs::msg::Curvature::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::Curvature::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::Curvature::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Curvature.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Curvature.h new file mode 100644 index 00000000000..619038269e0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Curvature.h @@ -0,0 +1,244 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Curvature.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURE_H_ + +#include "CurvatureConfidence.h" +#include "CurvatureValue.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(Curvature_SOURCE) +#define Curvature_DllAPI __declspec( dllexport ) +#else +#define Curvature_DllAPI __declspec( dllimport ) +#endif // Curvature_SOURCE +#else +#define Curvature_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define Curvature_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure Curvature defined by the user in the IDL file. + * @ingroup CURVATURE + */ + class Curvature + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Curvature(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Curvature(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::Curvature that will be copied. + */ + eProsima_user_DllExport Curvature( + const Curvature& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::Curvature that will be copied. + */ + eProsima_user_DllExport Curvature( + Curvature&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::Curvature that will be copied. + */ + eProsima_user_DllExport Curvature& operator =( + const Curvature& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::Curvature that will be copied. + */ + eProsima_user_DllExport Curvature& operator =( + Curvature&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::Curvature object to compare. + */ + eProsima_user_DllExport bool operator ==( + const Curvature& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::Curvature object to compare. + */ + eProsima_user_DllExport bool operator !=( + const Curvature& x) const; + + /*! + * @brief This function copies the value in member curvature_value + * @param _curvature_value New value to be copied in member curvature_value + */ + eProsima_user_DllExport void curvature_value( + const etsi_its_cam_msgs::msg::CurvatureValue& _curvature_value); + + /*! + * @brief This function moves the value in member curvature_value + * @param _curvature_value New value to be moved in member curvature_value + */ + eProsima_user_DllExport void curvature_value( + etsi_its_cam_msgs::msg::CurvatureValue&& _curvature_value); + + /*! + * @brief This function returns a constant reference to member curvature_value + * @return Constant reference to member curvature_value + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::CurvatureValue& curvature_value() const; + + /*! + * @brief This function returns a reference to member curvature_value + * @return Reference to member curvature_value + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::CurvatureValue& curvature_value(); + /*! + * @brief This function copies the value in member curvature_confidence + * @param _curvature_confidence New value to be copied in member curvature_confidence + */ + eProsima_user_DllExport void curvature_confidence( + const etsi_its_cam_msgs::msg::CurvatureConfidence& _curvature_confidence); + + /*! + * @brief This function moves the value in member curvature_confidence + * @param _curvature_confidence New value to be moved in member curvature_confidence + */ + eProsima_user_DllExport void curvature_confidence( + etsi_its_cam_msgs::msg::CurvatureConfidence&& _curvature_confidence); + + /*! + * @brief This function returns a constant reference to member curvature_confidence + * @return Constant reference to member curvature_confidence + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::CurvatureConfidence& curvature_confidence() const; + + /*! + * @brief This function returns a reference to member curvature_confidence + * @return Reference to member curvature_confidence + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::CurvatureConfidence& curvature_confidence(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::Curvature& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::CurvatureValue m_curvature_value; + etsi_its_cam_msgs::msg::CurvatureConfidence m_curvature_confidence; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationMode.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationMode.cxx new file mode 100644 index 00000000000..70e39822545 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationMode.cxx @@ -0,0 +1,187 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CurvatureCalculationMode.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CurvatureCalculationMode.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + +etsi_its_cam_msgs::msg::CurvatureCalculationMode::CurvatureCalculationMode() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@c446b14 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::CurvatureCalculationMode::~CurvatureCalculationMode() +{ +} + +etsi_its_cam_msgs::msg::CurvatureCalculationMode::CurvatureCalculationMode( + const CurvatureCalculationMode& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::CurvatureCalculationMode::CurvatureCalculationMode( + CurvatureCalculationMode&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::CurvatureCalculationMode& etsi_its_cam_msgs::msg::CurvatureCalculationMode::operator =( + const CurvatureCalculationMode& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::CurvatureCalculationMode& etsi_its_cam_msgs::msg::CurvatureCalculationMode::operator =( + CurvatureCalculationMode&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::CurvatureCalculationMode::operator ==( + const CurvatureCalculationMode& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::CurvatureCalculationMode::operator !=( + const CurvatureCalculationMode& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::CurvatureCalculationMode::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::CurvatureCalculationMode::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::CurvatureCalculationMode& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::CurvatureCalculationMode::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::CurvatureCalculationMode::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::CurvatureCalculationMode::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::CurvatureCalculationMode::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::CurvatureCalculationMode::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::CurvatureCalculationMode::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::CurvatureCalculationMode::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::CurvatureCalculationMode::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationMode.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationMode.h new file mode 100644 index 00000000000..6360629c264 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationMode.h @@ -0,0 +1,215 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CurvatureCalculationMode.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECALCULATIONMODE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECALCULATIONMODE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CurvatureCalculationMode_SOURCE) +#define CurvatureCalculationMode_DllAPI __declspec( dllexport ) +#else +#define CurvatureCalculationMode_DllAPI __declspec( dllimport ) +#endif // CurvatureCalculationMode_SOURCE +#else +#define CurvatureCalculationMode_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CurvatureCalculationMode_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace CurvatureCalculationMode_Constants { + const uint8_t YAW_RATE_USED = 0; + const uint8_t YAW_RATE_NOT_USED = 1; + const uint8_t UNAVAILABLE = 2; + } // namespace CurvatureCalculationMode_Constants + /*! + * @brief This class represents the structure CurvatureCalculationMode defined by the user in the IDL file. + * @ingroup CURVATURECALCULATIONMODE + */ + class CurvatureCalculationMode + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CurvatureCalculationMode(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CurvatureCalculationMode(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::CurvatureCalculationMode that will be copied. + */ + eProsima_user_DllExport CurvatureCalculationMode( + const CurvatureCalculationMode& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::CurvatureCalculationMode that will be copied. + */ + eProsima_user_DllExport CurvatureCalculationMode( + CurvatureCalculationMode&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::CurvatureCalculationMode that will be copied. + */ + eProsima_user_DllExport CurvatureCalculationMode& operator =( + const CurvatureCalculationMode& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::CurvatureCalculationMode that will be copied. + */ + eProsima_user_DllExport CurvatureCalculationMode& operator =( + CurvatureCalculationMode&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::CurvatureCalculationMode object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CurvatureCalculationMode& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::CurvatureCalculationMode object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CurvatureCalculationMode& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::CurvatureCalculationMode& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECALCULATIONMODE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationModePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationModePubSubTypes.cxx new file mode 100644 index 00000000000..b3a8fcb5ae1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationModePubSubTypes.cxx @@ -0,0 +1,182 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CurvatureCalculationModePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CurvatureCalculationModePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace CurvatureCalculationMode_Constants { + + + + + } //End of namespace CurvatureCalculationMode_Constants + CurvatureCalculationModePubSubType::CurvatureCalculationModePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::CurvatureCalculationMode_"); + auto type_size = CurvatureCalculationMode::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CurvatureCalculationMode::isKeyDefined(); + size_t keyLength = CurvatureCalculationMode::getKeyMaxCdrSerializedSize() > 16 ? + CurvatureCalculationMode::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CurvatureCalculationModePubSubType::~CurvatureCalculationModePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CurvatureCalculationModePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CurvatureCalculationMode* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CurvatureCalculationModePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CurvatureCalculationMode* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CurvatureCalculationModePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CurvatureCalculationModePubSubType::createData() + { + return reinterpret_cast(new CurvatureCalculationMode()); + } + + void CurvatureCalculationModePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CurvatureCalculationModePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CurvatureCalculationMode* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CurvatureCalculationMode::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CurvatureCalculationMode::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationModePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationModePubSubTypes.h new file mode 100644 index 00000000000..f0057bca0fe --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationModePubSubTypes.h @@ -0,0 +1,113 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CurvatureCalculationModePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECALCULATIONMODE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECALCULATIONMODE_PUBSUBTYPES_H_ + +#include +#include + +#include "CurvatureCalculationMode.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CurvatureCalculationMode is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace CurvatureCalculationMode_Constants + { + + + + } + /*! + * @brief This class represents the TopicDataType of the type CurvatureCalculationMode defined by the user in the IDL file. + * @ingroup CURVATURECALCULATIONMODE + */ + class CurvatureCalculationModePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CurvatureCalculationMode type; + + eProsima_user_DllExport CurvatureCalculationModePubSubType(); + + eProsima_user_DllExport virtual ~CurvatureCalculationModePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) CurvatureCalculationMode(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECALCULATIONMODE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidence.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidence.cxx new file mode 100644 index 00000000000..0c9a9650867 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidence.cxx @@ -0,0 +1,192 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CurvatureConfidence.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CurvatureConfidence.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + + + +etsi_its_cam_msgs::msg::CurvatureConfidence::CurvatureConfidence() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@76075d65 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::CurvatureConfidence::~CurvatureConfidence() +{ +} + +etsi_its_cam_msgs::msg::CurvatureConfidence::CurvatureConfidence( + const CurvatureConfidence& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::CurvatureConfidence::CurvatureConfidence( + CurvatureConfidence&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::CurvatureConfidence& etsi_its_cam_msgs::msg::CurvatureConfidence::operator =( + const CurvatureConfidence& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::CurvatureConfidence& etsi_its_cam_msgs::msg::CurvatureConfidence::operator =( + CurvatureConfidence&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::CurvatureConfidence::operator ==( + const CurvatureConfidence& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::CurvatureConfidence::operator !=( + const CurvatureConfidence& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::CurvatureConfidence::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::CurvatureConfidence::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::CurvatureConfidence& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::CurvatureConfidence::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::CurvatureConfidence::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::CurvatureConfidence::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::CurvatureConfidence::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::CurvatureConfidence::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::CurvatureConfidence::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::CurvatureConfidence::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::CurvatureConfidence::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidence.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidence.h new file mode 100644 index 00000000000..819fa5b5e23 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidence.h @@ -0,0 +1,220 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CurvatureConfidence.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECONFIDENCE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECONFIDENCE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CurvatureConfidence_SOURCE) +#define CurvatureConfidence_DllAPI __declspec( dllexport ) +#else +#define CurvatureConfidence_DllAPI __declspec( dllimport ) +#endif // CurvatureConfidence_SOURCE +#else +#define CurvatureConfidence_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CurvatureConfidence_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace CurvatureConfidence_Constants { + const uint8_t ONE_PER_METER_0_00002 = 0; + const uint8_t ONE_PER_METER_0_0001 = 1; + const uint8_t ONE_PER_METER_0_0005 = 2; + const uint8_t ONE_PER_METER_0_002 = 3; + const uint8_t ONE_PER_METER_0_01 = 4; + const uint8_t ONE_PER_METER_0_1 = 5; + const uint8_t OUT_OF_RANGE = 6; + const uint8_t UNAVAILABLE = 7; + } // namespace CurvatureConfidence_Constants + /*! + * @brief This class represents the structure CurvatureConfidence defined by the user in the IDL file. + * @ingroup CURVATURECONFIDENCE + */ + class CurvatureConfidence + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CurvatureConfidence(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CurvatureConfidence(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::CurvatureConfidence that will be copied. + */ + eProsima_user_DllExport CurvatureConfidence( + const CurvatureConfidence& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::CurvatureConfidence that will be copied. + */ + eProsima_user_DllExport CurvatureConfidence( + CurvatureConfidence&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::CurvatureConfidence that will be copied. + */ + eProsima_user_DllExport CurvatureConfidence& operator =( + const CurvatureConfidence& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::CurvatureConfidence that will be copied. + */ + eProsima_user_DllExport CurvatureConfidence& operator =( + CurvatureConfidence&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::CurvatureConfidence object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CurvatureConfidence& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::CurvatureConfidence object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CurvatureConfidence& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::CurvatureConfidence& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECONFIDENCE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidencePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidencePubSubTypes.cxx new file mode 100644 index 00000000000..7a16975794f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidencePubSubTypes.cxx @@ -0,0 +1,187 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CurvatureConfidencePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CurvatureConfidencePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace CurvatureConfidence_Constants { + + + + + + + + + + } //End of namespace CurvatureConfidence_Constants + CurvatureConfidencePubSubType::CurvatureConfidencePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::CurvatureConfidence_"); + auto type_size = CurvatureConfidence::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CurvatureConfidence::isKeyDefined(); + size_t keyLength = CurvatureConfidence::getKeyMaxCdrSerializedSize() > 16 ? + CurvatureConfidence::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CurvatureConfidencePubSubType::~CurvatureConfidencePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CurvatureConfidencePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CurvatureConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CurvatureConfidencePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CurvatureConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CurvatureConfidencePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CurvatureConfidencePubSubType::createData() + { + return reinterpret_cast(new CurvatureConfidence()); + } + + void CurvatureConfidencePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CurvatureConfidencePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CurvatureConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CurvatureConfidence::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CurvatureConfidence::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidencePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidencePubSubTypes.h new file mode 100644 index 00000000000..40a19ad810f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidencePubSubTypes.h @@ -0,0 +1,118 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CurvatureConfidencePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECONFIDENCE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECONFIDENCE_PUBSUBTYPES_H_ + +#include +#include + +#include "CurvatureConfidence.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CurvatureConfidence is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace CurvatureConfidence_Constants + { + + + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type CurvatureConfidence defined by the user in the IDL file. + * @ingroup CURVATURECONFIDENCE + */ + class CurvatureConfidencePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CurvatureConfidence type; + + eProsima_user_DllExport CurvatureConfidencePubSubType(); + + eProsima_user_DllExport virtual ~CurvatureConfidencePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) CurvatureConfidence(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECONFIDENCE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvaturePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvaturePubSubTypes.cxx new file mode 100644 index 00000000000..97ee8aab403 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvaturePubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CurvaturePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CurvaturePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + CurvaturePubSubType::CurvaturePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::Curvature_"); + auto type_size = Curvature::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = Curvature::isKeyDefined(); + size_t keyLength = Curvature::getKeyMaxCdrSerializedSize() > 16 ? + Curvature::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CurvaturePubSubType::~CurvaturePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CurvaturePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + Curvature* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CurvaturePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + Curvature* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CurvaturePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CurvaturePubSubType::createData() + { + return reinterpret_cast(new Curvature()); + } + + void CurvaturePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CurvaturePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + Curvature* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + Curvature::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || Curvature::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvaturePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvaturePubSubTypes.h new file mode 100644 index 00000000000..d8c5a516da9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvaturePubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CurvaturePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURE_PUBSUBTYPES_H_ + +#include +#include + +#include "Curvature.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated Curvature is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type Curvature defined by the user in the IDL file. + * @ingroup CURVATURE + */ + class CurvaturePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef Curvature type; + + eProsima_user_DllExport CurvaturePubSubType(); + + eProsima_user_DllExport virtual ~CurvaturePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) Curvature(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValue.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValue.cxx new file mode 100644 index 00000000000..d7890d2f515 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValue.cxx @@ -0,0 +1,188 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CurvatureValue.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CurvatureValue.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + +etsi_its_cam_msgs::msg::CurvatureValue::CurvatureValue() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@426e505c + m_value = 0; + +} + +etsi_its_cam_msgs::msg::CurvatureValue::~CurvatureValue() +{ +} + +etsi_its_cam_msgs::msg::CurvatureValue::CurvatureValue( + const CurvatureValue& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::CurvatureValue::CurvatureValue( + CurvatureValue&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::CurvatureValue& etsi_its_cam_msgs::msg::CurvatureValue::operator =( + const CurvatureValue& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::CurvatureValue& etsi_its_cam_msgs::msg::CurvatureValue::operator =( + CurvatureValue&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::CurvatureValue::operator ==( + const CurvatureValue& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::CurvatureValue::operator !=( + const CurvatureValue& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::CurvatureValue::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::CurvatureValue::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::CurvatureValue& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::CurvatureValue::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::CurvatureValue::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::CurvatureValue::value( + int16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int16_t etsi_its_cam_msgs::msg::CurvatureValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int16_t& etsi_its_cam_msgs::msg::CurvatureValue::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::CurvatureValue::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::CurvatureValue::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::CurvatureValue::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValue.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValue.h new file mode 100644 index 00000000000..e401f66b36c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValue.h @@ -0,0 +1,216 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CurvatureValue.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATUREVALUE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATUREVALUE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CurvatureValue_SOURCE) +#define CurvatureValue_DllAPI __declspec( dllexport ) +#else +#define CurvatureValue_DllAPI __declspec( dllimport ) +#endif // CurvatureValue_SOURCE +#else +#define CurvatureValue_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CurvatureValue_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace CurvatureValue_Constants { + const int16_t MIN = -1023; + const int16_t MAX = 1023; + const int16_t STRAIGHT = 0; + const int16_t UNAVAILABLE = 1023; + } // namespace CurvatureValue_Constants + /*! + * @brief This class represents the structure CurvatureValue defined by the user in the IDL file. + * @ingroup CURVATUREVALUE + */ + class CurvatureValue + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CurvatureValue(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CurvatureValue(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::CurvatureValue that will be copied. + */ + eProsima_user_DllExport CurvatureValue( + const CurvatureValue& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::CurvatureValue that will be copied. + */ + eProsima_user_DllExport CurvatureValue( + CurvatureValue&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::CurvatureValue that will be copied. + */ + eProsima_user_DllExport CurvatureValue& operator =( + const CurvatureValue& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::CurvatureValue that will be copied. + */ + eProsima_user_DllExport CurvatureValue& operator =( + CurvatureValue&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::CurvatureValue object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CurvatureValue& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::CurvatureValue object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CurvatureValue& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + int16_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport int16_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport int16_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::CurvatureValue& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + int16_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATUREVALUE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValuePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValuePubSubTypes.cxx new file mode 100644 index 00000000000..374e9c78405 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValuePubSubTypes.cxx @@ -0,0 +1,183 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CurvatureValuePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "CurvatureValuePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace CurvatureValue_Constants { + + + + + + } //End of namespace CurvatureValue_Constants + CurvatureValuePubSubType::CurvatureValuePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::CurvatureValue_"); + auto type_size = CurvatureValue::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = CurvatureValue::isKeyDefined(); + size_t keyLength = CurvatureValue::getKeyMaxCdrSerializedSize() > 16 ? + CurvatureValue::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + CurvatureValuePubSubType::~CurvatureValuePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool CurvatureValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + CurvatureValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool CurvatureValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + CurvatureValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function CurvatureValuePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* CurvatureValuePubSubType::createData() + { + return reinterpret_cast(new CurvatureValue()); + } + + void CurvatureValuePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool CurvatureValuePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + CurvatureValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + CurvatureValue::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || CurvatureValue::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValuePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValuePubSubTypes.h new file mode 100644 index 00000000000..e80800a19b5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValuePubSubTypes.h @@ -0,0 +1,114 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CurvatureValuePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATUREVALUE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATUREVALUE_PUBSUBTYPES_H_ + +#include +#include + +#include "CurvatureValue.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated CurvatureValue is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace CurvatureValue_Constants + { + + + + + } + /*! + * @brief This class represents the TopicDataType of the type CurvatureValue defined by the user in the IDL file. + * @ingroup CURVATUREVALUE + */ + class CurvatureValuePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef CurvatureValue type; + + eProsima_user_DllExport CurvatureValuePubSubType(); + + eProsima_user_DllExport virtual ~CurvatureValuePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) CurvatureValue(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATUREVALUE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasic.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasic.cxx new file mode 100644 index 00000000000..9c50fb7caf4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasic.cxx @@ -0,0 +1,204 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DangerousGoodsBasic.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "DangerousGoodsBasic.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + + + + + + + + + + + + + + + +etsi_its_cam_msgs::msg::DangerousGoodsBasic::DangerousGoodsBasic() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@71e9a896 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::DangerousGoodsBasic::~DangerousGoodsBasic() +{ +} + +etsi_its_cam_msgs::msg::DangerousGoodsBasic::DangerousGoodsBasic( + const DangerousGoodsBasic& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::DangerousGoodsBasic::DangerousGoodsBasic( + DangerousGoodsBasic&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::DangerousGoodsBasic& etsi_its_cam_msgs::msg::DangerousGoodsBasic::operator =( + const DangerousGoodsBasic& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::DangerousGoodsBasic& etsi_its_cam_msgs::msg::DangerousGoodsBasic::operator =( + DangerousGoodsBasic&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::DangerousGoodsBasic::operator ==( + const DangerousGoodsBasic& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::DangerousGoodsBasic::operator !=( + const DangerousGoodsBasic& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::DangerousGoodsBasic::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::DangerousGoodsBasic::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::DangerousGoodsBasic& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::DangerousGoodsBasic::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::DangerousGoodsBasic::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::DangerousGoodsBasic::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::DangerousGoodsBasic::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::DangerousGoodsBasic::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::DangerousGoodsBasic::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::DangerousGoodsBasic::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::DangerousGoodsBasic::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasic.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasic.h new file mode 100644 index 00000000000..9f551f046cd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasic.h @@ -0,0 +1,232 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DangerousGoodsBasic.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSBASIC_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSBASIC_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(DangerousGoodsBasic_SOURCE) +#define DangerousGoodsBasic_DllAPI __declspec( dllexport ) +#else +#define DangerousGoodsBasic_DllAPI __declspec( dllimport ) +#endif // DangerousGoodsBasic_SOURCE +#else +#define DangerousGoodsBasic_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define DangerousGoodsBasic_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace DangerousGoodsBasic_Constants { + const uint8_t EXPLOSIVES_1 = 0; + const uint8_t EXPLOSIVES_2 = 1; + const uint8_t EXPLOSIVES_3 = 2; + const uint8_t EXPLOSIVES_4 = 3; + const uint8_t EXPLOSIVES_5 = 4; + const uint8_t EXPLOSIVES_6 = 5; + const uint8_t FLAMMABLE_GASES = 6; + const uint8_t NON_FLAMMABLE_GASES = 7; + const uint8_t TOXIC_GASES = 8; + const uint8_t FLAMMABLE_LIQUIDS = 9; + const uint8_t FLAMMABLE_SOLIDS = 10; + const uint8_t SUBSTANCES_LIABLE_TO_SPONTANEOUS_COMBUSTION = 11; + const uint8_t SUBSTANCES_EMITTING_FLAMMABLE_GASES_UPON_CONTACT_WITH_WATER = 12; + const uint8_t OXIDIZING_SUBSTANCES = 13; + const uint8_t ORGANIC_PEROXIDES = 14; + const uint8_t TOXIC_SUBSTANCES = 15; + const uint8_t INFECTIOUS_SUBSTANCES = 16; + const uint8_t RADIOACTIVE_MATERIAL = 17; + const uint8_t CORROSIVE_SUBSTANCES = 18; + const uint8_t MISCELLANEOUS_DANGEROUS_SUBSTANCES = 19; + } // namespace DangerousGoodsBasic_Constants + /*! + * @brief This class represents the structure DangerousGoodsBasic defined by the user in the IDL file. + * @ingroup DANGEROUSGOODSBASIC + */ + class DangerousGoodsBasic + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport DangerousGoodsBasic(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~DangerousGoodsBasic(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::DangerousGoodsBasic that will be copied. + */ + eProsima_user_DllExport DangerousGoodsBasic( + const DangerousGoodsBasic& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::DangerousGoodsBasic that will be copied. + */ + eProsima_user_DllExport DangerousGoodsBasic( + DangerousGoodsBasic&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::DangerousGoodsBasic that will be copied. + */ + eProsima_user_DllExport DangerousGoodsBasic& operator =( + const DangerousGoodsBasic& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::DangerousGoodsBasic that will be copied. + */ + eProsima_user_DllExport DangerousGoodsBasic& operator =( + DangerousGoodsBasic&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::DangerousGoodsBasic object to compare. + */ + eProsima_user_DllExport bool operator ==( + const DangerousGoodsBasic& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::DangerousGoodsBasic object to compare. + */ + eProsima_user_DllExport bool operator !=( + const DangerousGoodsBasic& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::DangerousGoodsBasic& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSBASIC_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasicPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasicPubSubTypes.cxx new file mode 100644 index 00000000000..6c17c6ca8ce --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasicPubSubTypes.cxx @@ -0,0 +1,199 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DangerousGoodsBasicPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "DangerousGoodsBasicPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace DangerousGoodsBasic_Constants { + + + + + + + + + + + + + + + + + + + + + + } //End of namespace DangerousGoodsBasic_Constants + DangerousGoodsBasicPubSubType::DangerousGoodsBasicPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::DangerousGoodsBasic_"); + auto type_size = DangerousGoodsBasic::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = DangerousGoodsBasic::isKeyDefined(); + size_t keyLength = DangerousGoodsBasic::getKeyMaxCdrSerializedSize() > 16 ? + DangerousGoodsBasic::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + DangerousGoodsBasicPubSubType::~DangerousGoodsBasicPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool DangerousGoodsBasicPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + DangerousGoodsBasic* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool DangerousGoodsBasicPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + DangerousGoodsBasic* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function DangerousGoodsBasicPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* DangerousGoodsBasicPubSubType::createData() + { + return reinterpret_cast(new DangerousGoodsBasic()); + } + + void DangerousGoodsBasicPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool DangerousGoodsBasicPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + DangerousGoodsBasic* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + DangerousGoodsBasic::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || DangerousGoodsBasic::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasicPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasicPubSubTypes.h new file mode 100644 index 00000000000..515ef86930b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasicPubSubTypes.h @@ -0,0 +1,130 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DangerousGoodsBasicPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSBASIC_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSBASIC_PUBSUBTYPES_H_ + +#include +#include + +#include "DangerousGoodsBasic.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated DangerousGoodsBasic is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace DangerousGoodsBasic_Constants + { + + + + + + + + + + + + + + + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type DangerousGoodsBasic defined by the user in the IDL file. + * @ingroup DANGEROUSGOODSBASIC + */ + class DangerousGoodsBasicPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef DangerousGoodsBasic type; + + eProsima_user_DllExport DangerousGoodsBasicPubSubType(); + + eProsima_user_DllExport virtual ~DangerousGoodsBasicPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) DangerousGoodsBasic(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSBASIC_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainer.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainer.cxx new file mode 100644 index 00000000000..a3fd0ae5863 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainer.cxx @@ -0,0 +1,190 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DangerousGoodsContainer.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "DangerousGoodsContainer.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::DangerousGoodsContainer::DangerousGoodsContainer() +{ + // m_dangerous_goods_basic com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@2970a5bc + + +} + +etsi_its_cam_msgs::msg::DangerousGoodsContainer::~DangerousGoodsContainer() +{ +} + +etsi_its_cam_msgs::msg::DangerousGoodsContainer::DangerousGoodsContainer( + const DangerousGoodsContainer& x) +{ + m_dangerous_goods_basic = x.m_dangerous_goods_basic; +} + +etsi_its_cam_msgs::msg::DangerousGoodsContainer::DangerousGoodsContainer( + DangerousGoodsContainer&& x) +{ + m_dangerous_goods_basic = std::move(x.m_dangerous_goods_basic); +} + +etsi_its_cam_msgs::msg::DangerousGoodsContainer& etsi_its_cam_msgs::msg::DangerousGoodsContainer::operator =( + const DangerousGoodsContainer& x) +{ + + m_dangerous_goods_basic = x.m_dangerous_goods_basic; + + return *this; +} + +etsi_its_cam_msgs::msg::DangerousGoodsContainer& etsi_its_cam_msgs::msg::DangerousGoodsContainer::operator =( + DangerousGoodsContainer&& x) +{ + + m_dangerous_goods_basic = std::move(x.m_dangerous_goods_basic); + + return *this; +} + +bool etsi_its_cam_msgs::msg::DangerousGoodsContainer::operator ==( + const DangerousGoodsContainer& x) const +{ + + return (m_dangerous_goods_basic == x.m_dangerous_goods_basic); +} + +bool etsi_its_cam_msgs::msg::DangerousGoodsContainer::operator !=( + const DangerousGoodsContainer& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::DangerousGoodsContainer::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::DangerousGoodsBasic::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::DangerousGoodsContainer::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::DangerousGoodsContainer& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::DangerousGoodsBasic::getCdrSerializedSize(data.dangerous_goods_basic(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::DangerousGoodsContainer::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_dangerous_goods_basic; + +} + +void etsi_its_cam_msgs::msg::DangerousGoodsContainer::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_dangerous_goods_basic; +} + +/*! + * @brief This function copies the value in member dangerous_goods_basic + * @param _dangerous_goods_basic New value to be copied in member dangerous_goods_basic + */ +void etsi_its_cam_msgs::msg::DangerousGoodsContainer::dangerous_goods_basic( + const etsi_its_cam_msgs::msg::DangerousGoodsBasic& _dangerous_goods_basic) +{ + m_dangerous_goods_basic = _dangerous_goods_basic; +} + +/*! + * @brief This function moves the value in member dangerous_goods_basic + * @param _dangerous_goods_basic New value to be moved in member dangerous_goods_basic + */ +void etsi_its_cam_msgs::msg::DangerousGoodsContainer::dangerous_goods_basic( + etsi_its_cam_msgs::msg::DangerousGoodsBasic&& _dangerous_goods_basic) +{ + m_dangerous_goods_basic = std::move(_dangerous_goods_basic); +} + +/*! + * @brief This function returns a constant reference to member dangerous_goods_basic + * @return Constant reference to member dangerous_goods_basic + */ +const etsi_its_cam_msgs::msg::DangerousGoodsBasic& etsi_its_cam_msgs::msg::DangerousGoodsContainer::dangerous_goods_basic() const +{ + return m_dangerous_goods_basic; +} + +/*! + * @brief This function returns a reference to member dangerous_goods_basic + * @return Reference to member dangerous_goods_basic + */ +etsi_its_cam_msgs::msg::DangerousGoodsBasic& etsi_its_cam_msgs::msg::DangerousGoodsContainer::dangerous_goods_basic() +{ + return m_dangerous_goods_basic; +} + +size_t etsi_its_cam_msgs::msg::DangerousGoodsContainer::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::DangerousGoodsContainer::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::DangerousGoodsContainer::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainer.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainer.h new file mode 100644 index 00000000000..d4ba1a7263d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainer.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DangerousGoodsContainer.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSCONTAINER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSCONTAINER_H_ + +#include "DangerousGoodsBasic.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(DangerousGoodsContainer_SOURCE) +#define DangerousGoodsContainer_DllAPI __declspec( dllexport ) +#else +#define DangerousGoodsContainer_DllAPI __declspec( dllimport ) +#endif // DangerousGoodsContainer_SOURCE +#else +#define DangerousGoodsContainer_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define DangerousGoodsContainer_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure DangerousGoodsContainer defined by the user in the IDL file. + * @ingroup DANGEROUSGOODSCONTAINER + */ + class DangerousGoodsContainer + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport DangerousGoodsContainer(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~DangerousGoodsContainer(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::DangerousGoodsContainer that will be copied. + */ + eProsima_user_DllExport DangerousGoodsContainer( + const DangerousGoodsContainer& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::DangerousGoodsContainer that will be copied. + */ + eProsima_user_DllExport DangerousGoodsContainer( + DangerousGoodsContainer&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::DangerousGoodsContainer that will be copied. + */ + eProsima_user_DllExport DangerousGoodsContainer& operator =( + const DangerousGoodsContainer& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::DangerousGoodsContainer that will be copied. + */ + eProsima_user_DllExport DangerousGoodsContainer& operator =( + DangerousGoodsContainer&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::DangerousGoodsContainer object to compare. + */ + eProsima_user_DllExport bool operator ==( + const DangerousGoodsContainer& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::DangerousGoodsContainer object to compare. + */ + eProsima_user_DllExport bool operator !=( + const DangerousGoodsContainer& x) const; + + /*! + * @brief This function copies the value in member dangerous_goods_basic + * @param _dangerous_goods_basic New value to be copied in member dangerous_goods_basic + */ + eProsima_user_DllExport void dangerous_goods_basic( + const etsi_its_cam_msgs::msg::DangerousGoodsBasic& _dangerous_goods_basic); + + /*! + * @brief This function moves the value in member dangerous_goods_basic + * @param _dangerous_goods_basic New value to be moved in member dangerous_goods_basic + */ + eProsima_user_DllExport void dangerous_goods_basic( + etsi_its_cam_msgs::msg::DangerousGoodsBasic&& _dangerous_goods_basic); + + /*! + * @brief This function returns a constant reference to member dangerous_goods_basic + * @return Constant reference to member dangerous_goods_basic + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::DangerousGoodsBasic& dangerous_goods_basic() const; + + /*! + * @brief This function returns a reference to member dangerous_goods_basic + * @return Reference to member dangerous_goods_basic + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::DangerousGoodsBasic& dangerous_goods_basic(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::DangerousGoodsContainer& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::DangerousGoodsBasic m_dangerous_goods_basic; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSCONTAINER_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainerPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainerPubSubTypes.cxx new file mode 100644 index 00000000000..d535ebf3c23 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainerPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DangerousGoodsContainerPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "DangerousGoodsContainerPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + DangerousGoodsContainerPubSubType::DangerousGoodsContainerPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::DangerousGoodsContainer_"); + auto type_size = DangerousGoodsContainer::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = DangerousGoodsContainer::isKeyDefined(); + size_t keyLength = DangerousGoodsContainer::getKeyMaxCdrSerializedSize() > 16 ? + DangerousGoodsContainer::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + DangerousGoodsContainerPubSubType::~DangerousGoodsContainerPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool DangerousGoodsContainerPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + DangerousGoodsContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool DangerousGoodsContainerPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + DangerousGoodsContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function DangerousGoodsContainerPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* DangerousGoodsContainerPubSubType::createData() + { + return reinterpret_cast(new DangerousGoodsContainer()); + } + + void DangerousGoodsContainerPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool DangerousGoodsContainerPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + DangerousGoodsContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + DangerousGoodsContainer::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || DangerousGoodsContainer::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainerPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainerPubSubTypes.h new file mode 100644 index 00000000000..ca101eaae8d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainerPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DangerousGoodsContainerPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSCONTAINER_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSCONTAINER_PUBSUBTYPES_H_ + +#include +#include + +#include "DangerousGoodsContainer.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated DangerousGoodsContainer is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type DangerousGoodsContainer defined by the user in the IDL file. + * @ingroup DANGEROUSGOODSCONTAINER + */ + class DangerousGoodsContainerPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef DangerousGoodsContainer type; + + eProsima_user_DllExport DangerousGoodsContainerPubSubType(); + + eProsima_user_DllExport virtual ~DangerousGoodsContainerPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) DangerousGoodsContainer(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSCONTAINER_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitude.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitude.cxx new file mode 100644 index 00000000000..bf1d8b57db6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitude.cxx @@ -0,0 +1,189 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DeltaAltitude.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "DeltaAltitude.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + +etsi_its_cam_msgs::msg::DeltaAltitude::DeltaAltitude() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@bae47a0 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::DeltaAltitude::~DeltaAltitude() +{ +} + +etsi_its_cam_msgs::msg::DeltaAltitude::DeltaAltitude( + const DeltaAltitude& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::DeltaAltitude::DeltaAltitude( + DeltaAltitude&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::DeltaAltitude& etsi_its_cam_msgs::msg::DeltaAltitude::operator =( + const DeltaAltitude& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::DeltaAltitude& etsi_its_cam_msgs::msg::DeltaAltitude::operator =( + DeltaAltitude&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::DeltaAltitude::operator ==( + const DeltaAltitude& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::DeltaAltitude::operator !=( + const DeltaAltitude& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::DeltaAltitude::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::DeltaAltitude::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::DeltaAltitude& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::DeltaAltitude::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::DeltaAltitude::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::DeltaAltitude::value( + int16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int16_t etsi_its_cam_msgs::msg::DeltaAltitude::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int16_t& etsi_its_cam_msgs::msg::DeltaAltitude::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::DeltaAltitude::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::DeltaAltitude::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::DeltaAltitude::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitude.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitude.h new file mode 100644 index 00000000000..a033de2a66e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitude.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DeltaAltitude.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAALTITUDE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAALTITUDE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(DeltaAltitude_SOURCE) +#define DeltaAltitude_DllAPI __declspec( dllexport ) +#else +#define DeltaAltitude_DllAPI __declspec( dllimport ) +#endif // DeltaAltitude_SOURCE +#else +#define DeltaAltitude_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define DeltaAltitude_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace DeltaAltitude_Constants { + const int16_t MIN = -12700; + const int16_t MAX = 12800; + const int16_t ONE_CENTIMETER_UP = 1; + const int16_t ONE_CENTIMETER_DOWN = -1; + const int16_t UNAVAILABLE = 12800; + } // namespace DeltaAltitude_Constants + /*! + * @brief This class represents the structure DeltaAltitude defined by the user in the IDL file. + * @ingroup DELTAALTITUDE + */ + class DeltaAltitude + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport DeltaAltitude(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~DeltaAltitude(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::DeltaAltitude that will be copied. + */ + eProsima_user_DllExport DeltaAltitude( + const DeltaAltitude& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::DeltaAltitude that will be copied. + */ + eProsima_user_DllExport DeltaAltitude( + DeltaAltitude&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::DeltaAltitude that will be copied. + */ + eProsima_user_DllExport DeltaAltitude& operator =( + const DeltaAltitude& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::DeltaAltitude that will be copied. + */ + eProsima_user_DllExport DeltaAltitude& operator =( + DeltaAltitude&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::DeltaAltitude object to compare. + */ + eProsima_user_DllExport bool operator ==( + const DeltaAltitude& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::DeltaAltitude object to compare. + */ + eProsima_user_DllExport bool operator !=( + const DeltaAltitude& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + int16_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport int16_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport int16_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::DeltaAltitude& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + int16_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAALTITUDE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitudePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitudePubSubTypes.cxx new file mode 100644 index 00000000000..9ceeff8f1ee --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitudePubSubTypes.cxx @@ -0,0 +1,184 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DeltaAltitudePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "DeltaAltitudePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace DeltaAltitude_Constants { + + + + + + + } //End of namespace DeltaAltitude_Constants + DeltaAltitudePubSubType::DeltaAltitudePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::DeltaAltitude_"); + auto type_size = DeltaAltitude::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = DeltaAltitude::isKeyDefined(); + size_t keyLength = DeltaAltitude::getKeyMaxCdrSerializedSize() > 16 ? + DeltaAltitude::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + DeltaAltitudePubSubType::~DeltaAltitudePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool DeltaAltitudePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + DeltaAltitude* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool DeltaAltitudePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + DeltaAltitude* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function DeltaAltitudePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* DeltaAltitudePubSubType::createData() + { + return reinterpret_cast(new DeltaAltitude()); + } + + void DeltaAltitudePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool DeltaAltitudePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + DeltaAltitude* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + DeltaAltitude::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || DeltaAltitude::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitudePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitudePubSubTypes.h new file mode 100644 index 00000000000..ba08c1fc281 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitudePubSubTypes.h @@ -0,0 +1,115 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DeltaAltitudePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAALTITUDE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAALTITUDE_PUBSUBTYPES_H_ + +#include +#include + +#include "DeltaAltitude.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated DeltaAltitude is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace DeltaAltitude_Constants + { + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type DeltaAltitude defined by the user in the IDL file. + * @ingroup DELTAALTITUDE + */ + class DeltaAltitudePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef DeltaAltitude type; + + eProsima_user_DllExport DeltaAltitudePubSubType(); + + eProsima_user_DllExport virtual ~DeltaAltitudePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) DeltaAltitude(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAALTITUDE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitude.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitude.cxx new file mode 100644 index 00000000000..2554cd0b344 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitude.cxx @@ -0,0 +1,189 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DeltaLatitude.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "DeltaLatitude.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + +etsi_its_cam_msgs::msg::DeltaLatitude::DeltaLatitude() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@3a71c100 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::DeltaLatitude::~DeltaLatitude() +{ +} + +etsi_its_cam_msgs::msg::DeltaLatitude::DeltaLatitude( + const DeltaLatitude& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::DeltaLatitude::DeltaLatitude( + DeltaLatitude&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::DeltaLatitude& etsi_its_cam_msgs::msg::DeltaLatitude::operator =( + const DeltaLatitude& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::DeltaLatitude& etsi_its_cam_msgs::msg::DeltaLatitude::operator =( + DeltaLatitude&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::DeltaLatitude::operator ==( + const DeltaLatitude& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::DeltaLatitude::operator !=( + const DeltaLatitude& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::DeltaLatitude::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::DeltaLatitude::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::DeltaLatitude& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::DeltaLatitude::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::DeltaLatitude::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::DeltaLatitude::value( + int32_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int32_t etsi_its_cam_msgs::msg::DeltaLatitude::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int32_t& etsi_its_cam_msgs::msg::DeltaLatitude::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::DeltaLatitude::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::DeltaLatitude::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::DeltaLatitude::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitude.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitude.h new file mode 100644 index 00000000000..1d88654a54b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitude.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DeltaLatitude.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALATITUDE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALATITUDE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(DeltaLatitude_SOURCE) +#define DeltaLatitude_DllAPI __declspec( dllexport ) +#else +#define DeltaLatitude_DllAPI __declspec( dllimport ) +#endif // DeltaLatitude_SOURCE +#else +#define DeltaLatitude_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define DeltaLatitude_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace DeltaLatitude_Constants { + const int32_t MIN = -131071; + const int32_t MAX = 131072; + const int32_t ONE_MICRODEGREE_NORTH = 10; + const int32_t ONE_MICRODEGREE_SOUTH = -10; + const int32_t UNAVAILABLE = 131072; + } // namespace DeltaLatitude_Constants + /*! + * @brief This class represents the structure DeltaLatitude defined by the user in the IDL file. + * @ingroup DELTALATITUDE + */ + class DeltaLatitude + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport DeltaLatitude(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~DeltaLatitude(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::DeltaLatitude that will be copied. + */ + eProsima_user_DllExport DeltaLatitude( + const DeltaLatitude& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::DeltaLatitude that will be copied. + */ + eProsima_user_DllExport DeltaLatitude( + DeltaLatitude&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::DeltaLatitude that will be copied. + */ + eProsima_user_DllExport DeltaLatitude& operator =( + const DeltaLatitude& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::DeltaLatitude that will be copied. + */ + eProsima_user_DllExport DeltaLatitude& operator =( + DeltaLatitude&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::DeltaLatitude object to compare. + */ + eProsima_user_DllExport bool operator ==( + const DeltaLatitude& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::DeltaLatitude object to compare. + */ + eProsima_user_DllExport bool operator !=( + const DeltaLatitude& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + int32_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport int32_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport int32_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::DeltaLatitude& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + int32_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALATITUDE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitudePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitudePubSubTypes.cxx new file mode 100644 index 00000000000..52d49bf7fd5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitudePubSubTypes.cxx @@ -0,0 +1,184 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DeltaLatitudePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "DeltaLatitudePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace DeltaLatitude_Constants { + + + + + + + } //End of namespace DeltaLatitude_Constants + DeltaLatitudePubSubType::DeltaLatitudePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::DeltaLatitude_"); + auto type_size = DeltaLatitude::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = DeltaLatitude::isKeyDefined(); + size_t keyLength = DeltaLatitude::getKeyMaxCdrSerializedSize() > 16 ? + DeltaLatitude::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + DeltaLatitudePubSubType::~DeltaLatitudePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool DeltaLatitudePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + DeltaLatitude* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool DeltaLatitudePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + DeltaLatitude* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function DeltaLatitudePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* DeltaLatitudePubSubType::createData() + { + return reinterpret_cast(new DeltaLatitude()); + } + + void DeltaLatitudePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool DeltaLatitudePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + DeltaLatitude* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + DeltaLatitude::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || DeltaLatitude::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitudePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitudePubSubTypes.h new file mode 100644 index 00000000000..e20b6656498 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitudePubSubTypes.h @@ -0,0 +1,115 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DeltaLatitudePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALATITUDE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALATITUDE_PUBSUBTYPES_H_ + +#include +#include + +#include "DeltaLatitude.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated DeltaLatitude is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace DeltaLatitude_Constants + { + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type DeltaLatitude defined by the user in the IDL file. + * @ingroup DELTALATITUDE + */ + class DeltaLatitudePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef DeltaLatitude type; + + eProsima_user_DllExport DeltaLatitudePubSubType(); + + eProsima_user_DllExport virtual ~DeltaLatitudePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) DeltaLatitude(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALATITUDE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitude.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitude.cxx new file mode 100644 index 00000000000..8c1e526a6d4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitude.cxx @@ -0,0 +1,189 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DeltaLongitude.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "DeltaLongitude.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + +etsi_its_cam_msgs::msg::DeltaLongitude::DeltaLongitude() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@26d10f2e + m_value = 0; + +} + +etsi_its_cam_msgs::msg::DeltaLongitude::~DeltaLongitude() +{ +} + +etsi_its_cam_msgs::msg::DeltaLongitude::DeltaLongitude( + const DeltaLongitude& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::DeltaLongitude::DeltaLongitude( + DeltaLongitude&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::DeltaLongitude& etsi_its_cam_msgs::msg::DeltaLongitude::operator =( + const DeltaLongitude& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::DeltaLongitude& etsi_its_cam_msgs::msg::DeltaLongitude::operator =( + DeltaLongitude&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::DeltaLongitude::operator ==( + const DeltaLongitude& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::DeltaLongitude::operator !=( + const DeltaLongitude& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::DeltaLongitude::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::DeltaLongitude::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::DeltaLongitude& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::DeltaLongitude::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::DeltaLongitude::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::DeltaLongitude::value( + int32_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int32_t etsi_its_cam_msgs::msg::DeltaLongitude::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int32_t& etsi_its_cam_msgs::msg::DeltaLongitude::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::DeltaLongitude::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::DeltaLongitude::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::DeltaLongitude::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitude.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitude.h new file mode 100644 index 00000000000..26139eacc05 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitude.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DeltaLongitude.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALONGITUDE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALONGITUDE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(DeltaLongitude_SOURCE) +#define DeltaLongitude_DllAPI __declspec( dllexport ) +#else +#define DeltaLongitude_DllAPI __declspec( dllimport ) +#endif // DeltaLongitude_SOURCE +#else +#define DeltaLongitude_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define DeltaLongitude_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace DeltaLongitude_Constants { + const int32_t MIN = -131071; + const int32_t MAX = 131072; + const int32_t ONE_MICRODEGREE_EAST = 10; + const int32_t ONE_MICRODEGREE_WEST = -10; + const int32_t UNAVAILABLE = 131072; + } // namespace DeltaLongitude_Constants + /*! + * @brief This class represents the structure DeltaLongitude defined by the user in the IDL file. + * @ingroup DELTALONGITUDE + */ + class DeltaLongitude + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport DeltaLongitude(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~DeltaLongitude(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::DeltaLongitude that will be copied. + */ + eProsima_user_DllExport DeltaLongitude( + const DeltaLongitude& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::DeltaLongitude that will be copied. + */ + eProsima_user_DllExport DeltaLongitude( + DeltaLongitude&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::DeltaLongitude that will be copied. + */ + eProsima_user_DllExport DeltaLongitude& operator =( + const DeltaLongitude& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::DeltaLongitude that will be copied. + */ + eProsima_user_DllExport DeltaLongitude& operator =( + DeltaLongitude&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::DeltaLongitude object to compare. + */ + eProsima_user_DllExport bool operator ==( + const DeltaLongitude& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::DeltaLongitude object to compare. + */ + eProsima_user_DllExport bool operator !=( + const DeltaLongitude& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + int32_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport int32_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport int32_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::DeltaLongitude& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + int32_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALONGITUDE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitudePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitudePubSubTypes.cxx new file mode 100644 index 00000000000..bd386e71f01 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitudePubSubTypes.cxx @@ -0,0 +1,184 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DeltaLongitudePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "DeltaLongitudePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace DeltaLongitude_Constants { + + + + + + + } //End of namespace DeltaLongitude_Constants + DeltaLongitudePubSubType::DeltaLongitudePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::DeltaLongitude_"); + auto type_size = DeltaLongitude::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = DeltaLongitude::isKeyDefined(); + size_t keyLength = DeltaLongitude::getKeyMaxCdrSerializedSize() > 16 ? + DeltaLongitude::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + DeltaLongitudePubSubType::~DeltaLongitudePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool DeltaLongitudePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + DeltaLongitude* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool DeltaLongitudePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + DeltaLongitude* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function DeltaLongitudePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* DeltaLongitudePubSubType::createData() + { + return reinterpret_cast(new DeltaLongitude()); + } + + void DeltaLongitudePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool DeltaLongitudePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + DeltaLongitude* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + DeltaLongitude::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || DeltaLongitude::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitudePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitudePubSubTypes.h new file mode 100644 index 00000000000..cfe9901a5e7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitudePubSubTypes.h @@ -0,0 +1,115 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DeltaLongitudePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALONGITUDE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALONGITUDE_PUBSUBTYPES_H_ + +#include +#include + +#include "DeltaLongitude.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated DeltaLongitude is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace DeltaLongitude_Constants + { + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type DeltaLongitude defined by the user in the IDL file. + * @ingroup DELTALONGITUDE + */ + class DeltaLongitudePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef DeltaLongitude type; + + eProsima_user_DllExport DeltaLongitudePubSubType(); + + eProsima_user_DllExport virtual ~DeltaLongitudePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) DeltaLongitude(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALONGITUDE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePosition.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePosition.cxx new file mode 100644 index 00000000000..67bf0d0c59e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePosition.cxx @@ -0,0 +1,286 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DeltaReferencePosition.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "DeltaReferencePosition.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::DeltaReferencePosition::DeltaReferencePosition() +{ + // m_delta_latitude com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@42deb43a + + // m_delta_longitude com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@1deb2c43 + + // m_delta_altitude com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@3bb9efbc + + +} + +etsi_its_cam_msgs::msg::DeltaReferencePosition::~DeltaReferencePosition() +{ + + +} + +etsi_its_cam_msgs::msg::DeltaReferencePosition::DeltaReferencePosition( + const DeltaReferencePosition& x) +{ + m_delta_latitude = x.m_delta_latitude; + m_delta_longitude = x.m_delta_longitude; + m_delta_altitude = x.m_delta_altitude; +} + +etsi_its_cam_msgs::msg::DeltaReferencePosition::DeltaReferencePosition( + DeltaReferencePosition&& x) +{ + m_delta_latitude = std::move(x.m_delta_latitude); + m_delta_longitude = std::move(x.m_delta_longitude); + m_delta_altitude = std::move(x.m_delta_altitude); +} + +etsi_its_cam_msgs::msg::DeltaReferencePosition& etsi_its_cam_msgs::msg::DeltaReferencePosition::operator =( + const DeltaReferencePosition& x) +{ + + m_delta_latitude = x.m_delta_latitude; + m_delta_longitude = x.m_delta_longitude; + m_delta_altitude = x.m_delta_altitude; + + return *this; +} + +etsi_its_cam_msgs::msg::DeltaReferencePosition& etsi_its_cam_msgs::msg::DeltaReferencePosition::operator =( + DeltaReferencePosition&& x) +{ + + m_delta_latitude = std::move(x.m_delta_latitude); + m_delta_longitude = std::move(x.m_delta_longitude); + m_delta_altitude = std::move(x.m_delta_altitude); + + return *this; +} + +bool etsi_its_cam_msgs::msg::DeltaReferencePosition::operator ==( + const DeltaReferencePosition& x) const +{ + + return (m_delta_latitude == x.m_delta_latitude && m_delta_longitude == x.m_delta_longitude && m_delta_altitude == x.m_delta_altitude); +} + +bool etsi_its_cam_msgs::msg::DeltaReferencePosition::operator !=( + const DeltaReferencePosition& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::DeltaReferencePosition::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::DeltaLatitude::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::DeltaLongitude::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::DeltaAltitude::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::DeltaReferencePosition::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::DeltaReferencePosition& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::DeltaLatitude::getCdrSerializedSize(data.delta_latitude(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::DeltaLongitude::getCdrSerializedSize(data.delta_longitude(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::DeltaAltitude::getCdrSerializedSize(data.delta_altitude(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::DeltaReferencePosition::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_delta_latitude; + scdr << m_delta_longitude; + scdr << m_delta_altitude; + +} + +void etsi_its_cam_msgs::msg::DeltaReferencePosition::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_delta_latitude; + dcdr >> m_delta_longitude; + dcdr >> m_delta_altitude; +} + +/*! + * @brief This function copies the value in member delta_latitude + * @param _delta_latitude New value to be copied in member delta_latitude + */ +void etsi_its_cam_msgs::msg::DeltaReferencePosition::delta_latitude( + const etsi_its_cam_msgs::msg::DeltaLatitude& _delta_latitude) +{ + m_delta_latitude = _delta_latitude; +} + +/*! + * @brief This function moves the value in member delta_latitude + * @param _delta_latitude New value to be moved in member delta_latitude + */ +void etsi_its_cam_msgs::msg::DeltaReferencePosition::delta_latitude( + etsi_its_cam_msgs::msg::DeltaLatitude&& _delta_latitude) +{ + m_delta_latitude = std::move(_delta_latitude); +} + +/*! + * @brief This function returns a constant reference to member delta_latitude + * @return Constant reference to member delta_latitude + */ +const etsi_its_cam_msgs::msg::DeltaLatitude& etsi_its_cam_msgs::msg::DeltaReferencePosition::delta_latitude() const +{ + return m_delta_latitude; +} + +/*! + * @brief This function returns a reference to member delta_latitude + * @return Reference to member delta_latitude + */ +etsi_its_cam_msgs::msg::DeltaLatitude& etsi_its_cam_msgs::msg::DeltaReferencePosition::delta_latitude() +{ + return m_delta_latitude; +} +/*! + * @brief This function copies the value in member delta_longitude + * @param _delta_longitude New value to be copied in member delta_longitude + */ +void etsi_its_cam_msgs::msg::DeltaReferencePosition::delta_longitude( + const etsi_its_cam_msgs::msg::DeltaLongitude& _delta_longitude) +{ + m_delta_longitude = _delta_longitude; +} + +/*! + * @brief This function moves the value in member delta_longitude + * @param _delta_longitude New value to be moved in member delta_longitude + */ +void etsi_its_cam_msgs::msg::DeltaReferencePosition::delta_longitude( + etsi_its_cam_msgs::msg::DeltaLongitude&& _delta_longitude) +{ + m_delta_longitude = std::move(_delta_longitude); +} + +/*! + * @brief This function returns a constant reference to member delta_longitude + * @return Constant reference to member delta_longitude + */ +const etsi_its_cam_msgs::msg::DeltaLongitude& etsi_its_cam_msgs::msg::DeltaReferencePosition::delta_longitude() const +{ + return m_delta_longitude; +} + +/*! + * @brief This function returns a reference to member delta_longitude + * @return Reference to member delta_longitude + */ +etsi_its_cam_msgs::msg::DeltaLongitude& etsi_its_cam_msgs::msg::DeltaReferencePosition::delta_longitude() +{ + return m_delta_longitude; +} +/*! + * @brief This function copies the value in member delta_altitude + * @param _delta_altitude New value to be copied in member delta_altitude + */ +void etsi_its_cam_msgs::msg::DeltaReferencePosition::delta_altitude( + const etsi_its_cam_msgs::msg::DeltaAltitude& _delta_altitude) +{ + m_delta_altitude = _delta_altitude; +} + +/*! + * @brief This function moves the value in member delta_altitude + * @param _delta_altitude New value to be moved in member delta_altitude + */ +void etsi_its_cam_msgs::msg::DeltaReferencePosition::delta_altitude( + etsi_its_cam_msgs::msg::DeltaAltitude&& _delta_altitude) +{ + m_delta_altitude = std::move(_delta_altitude); +} + +/*! + * @brief This function returns a constant reference to member delta_altitude + * @return Constant reference to member delta_altitude + */ +const etsi_its_cam_msgs::msg::DeltaAltitude& etsi_its_cam_msgs::msg::DeltaReferencePosition::delta_altitude() const +{ + return m_delta_altitude; +} + +/*! + * @brief This function returns a reference to member delta_altitude + * @return Reference to member delta_altitude + */ +etsi_its_cam_msgs::msg::DeltaAltitude& etsi_its_cam_msgs::msg::DeltaReferencePosition::delta_altitude() +{ + return m_delta_altitude; +} + +size_t etsi_its_cam_msgs::msg::DeltaReferencePosition::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::DeltaReferencePosition::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::DeltaReferencePosition::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePosition.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePosition.h new file mode 100644 index 00000000000..ce2a1c5045b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePosition.h @@ -0,0 +1,271 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DeltaReferencePosition.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAREFERENCEPOSITION_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAREFERENCEPOSITION_H_ + +#include "DeltaLongitude.h" +#include "DeltaAltitude.h" +#include "DeltaLatitude.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(DeltaReferencePosition_SOURCE) +#define DeltaReferencePosition_DllAPI __declspec( dllexport ) +#else +#define DeltaReferencePosition_DllAPI __declspec( dllimport ) +#endif // DeltaReferencePosition_SOURCE +#else +#define DeltaReferencePosition_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define DeltaReferencePosition_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure DeltaReferencePosition defined by the user in the IDL file. + * @ingroup DELTAREFERENCEPOSITION + */ + class DeltaReferencePosition + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport DeltaReferencePosition(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~DeltaReferencePosition(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::DeltaReferencePosition that will be copied. + */ + eProsima_user_DllExport DeltaReferencePosition( + const DeltaReferencePosition& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::DeltaReferencePosition that will be copied. + */ + eProsima_user_DllExport DeltaReferencePosition( + DeltaReferencePosition&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::DeltaReferencePosition that will be copied. + */ + eProsima_user_DllExport DeltaReferencePosition& operator =( + const DeltaReferencePosition& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::DeltaReferencePosition that will be copied. + */ + eProsima_user_DllExport DeltaReferencePosition& operator =( + DeltaReferencePosition&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::DeltaReferencePosition object to compare. + */ + eProsima_user_DllExport bool operator ==( + const DeltaReferencePosition& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::DeltaReferencePosition object to compare. + */ + eProsima_user_DllExport bool operator !=( + const DeltaReferencePosition& x) const; + + /*! + * @brief This function copies the value in member delta_latitude + * @param _delta_latitude New value to be copied in member delta_latitude + */ + eProsima_user_DllExport void delta_latitude( + const etsi_its_cam_msgs::msg::DeltaLatitude& _delta_latitude); + + /*! + * @brief This function moves the value in member delta_latitude + * @param _delta_latitude New value to be moved in member delta_latitude + */ + eProsima_user_DllExport void delta_latitude( + etsi_its_cam_msgs::msg::DeltaLatitude&& _delta_latitude); + + /*! + * @brief This function returns a constant reference to member delta_latitude + * @return Constant reference to member delta_latitude + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::DeltaLatitude& delta_latitude() const; + + /*! + * @brief This function returns a reference to member delta_latitude + * @return Reference to member delta_latitude + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::DeltaLatitude& delta_latitude(); + /*! + * @brief This function copies the value in member delta_longitude + * @param _delta_longitude New value to be copied in member delta_longitude + */ + eProsima_user_DllExport void delta_longitude( + const etsi_its_cam_msgs::msg::DeltaLongitude& _delta_longitude); + + /*! + * @brief This function moves the value in member delta_longitude + * @param _delta_longitude New value to be moved in member delta_longitude + */ + eProsima_user_DllExport void delta_longitude( + etsi_its_cam_msgs::msg::DeltaLongitude&& _delta_longitude); + + /*! + * @brief This function returns a constant reference to member delta_longitude + * @return Constant reference to member delta_longitude + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::DeltaLongitude& delta_longitude() const; + + /*! + * @brief This function returns a reference to member delta_longitude + * @return Reference to member delta_longitude + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::DeltaLongitude& delta_longitude(); + /*! + * @brief This function copies the value in member delta_altitude + * @param _delta_altitude New value to be copied in member delta_altitude + */ + eProsima_user_DllExport void delta_altitude( + const etsi_its_cam_msgs::msg::DeltaAltitude& _delta_altitude); + + /*! + * @brief This function moves the value in member delta_altitude + * @param _delta_altitude New value to be moved in member delta_altitude + */ + eProsima_user_DllExport void delta_altitude( + etsi_its_cam_msgs::msg::DeltaAltitude&& _delta_altitude); + + /*! + * @brief This function returns a constant reference to member delta_altitude + * @return Constant reference to member delta_altitude + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::DeltaAltitude& delta_altitude() const; + + /*! + * @brief This function returns a reference to member delta_altitude + * @return Reference to member delta_altitude + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::DeltaAltitude& delta_altitude(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::DeltaReferencePosition& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::DeltaLatitude m_delta_latitude; + etsi_its_cam_msgs::msg::DeltaLongitude m_delta_longitude; + etsi_its_cam_msgs::msg::DeltaAltitude m_delta_altitude; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAREFERENCEPOSITION_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePositionPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePositionPubSubTypes.cxx new file mode 100644 index 00000000000..474fa36d3d7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePositionPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DeltaReferencePositionPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "DeltaReferencePositionPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + DeltaReferencePositionPubSubType::DeltaReferencePositionPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::DeltaReferencePosition_"); + auto type_size = DeltaReferencePosition::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = DeltaReferencePosition::isKeyDefined(); + size_t keyLength = DeltaReferencePosition::getKeyMaxCdrSerializedSize() > 16 ? + DeltaReferencePosition::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + DeltaReferencePositionPubSubType::~DeltaReferencePositionPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool DeltaReferencePositionPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + DeltaReferencePosition* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool DeltaReferencePositionPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + DeltaReferencePosition* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function DeltaReferencePositionPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* DeltaReferencePositionPubSubType::createData() + { + return reinterpret_cast(new DeltaReferencePosition()); + } + + void DeltaReferencePositionPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool DeltaReferencePositionPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + DeltaReferencePosition* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + DeltaReferencePosition::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || DeltaReferencePosition::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePositionPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePositionPubSubTypes.h new file mode 100644 index 00000000000..28c77e36f97 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePositionPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DeltaReferencePositionPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAREFERENCEPOSITION_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAREFERENCEPOSITION_PUBSUBTYPES_H_ + +#include +#include + +#include "DeltaReferencePosition.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated DeltaReferencePosition is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type DeltaReferencePosition defined by the user in the IDL file. + * @ingroup DELTAREFERENCEPOSITION + */ + class DeltaReferencePositionPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef DeltaReferencePosition type; + + eProsima_user_DllExport DeltaReferencePositionPubSubType(); + + eProsima_user_DllExport virtual ~DeltaReferencePositionPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) DeltaReferencePosition(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAREFERENCEPOSITION_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirection.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirection.cxx new file mode 100644 index 00000000000..b1b093bf57b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirection.cxx @@ -0,0 +1,187 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DriveDirection.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "DriveDirection.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + +etsi_its_cam_msgs::msg::DriveDirection::DriveDirection() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@6dd93a21 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::DriveDirection::~DriveDirection() +{ +} + +etsi_its_cam_msgs::msg::DriveDirection::DriveDirection( + const DriveDirection& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::DriveDirection::DriveDirection( + DriveDirection&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::DriveDirection& etsi_its_cam_msgs::msg::DriveDirection::operator =( + const DriveDirection& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::DriveDirection& etsi_its_cam_msgs::msg::DriveDirection::operator =( + DriveDirection&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::DriveDirection::operator ==( + const DriveDirection& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::DriveDirection::operator !=( + const DriveDirection& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::DriveDirection::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::DriveDirection::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::DriveDirection& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::DriveDirection::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::DriveDirection::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::DriveDirection::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::DriveDirection::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::DriveDirection::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::DriveDirection::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::DriveDirection::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::DriveDirection::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirection.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirection.h new file mode 100644 index 00000000000..f36db68b856 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirection.h @@ -0,0 +1,215 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DriveDirection.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVEDIRECTION_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVEDIRECTION_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(DriveDirection_SOURCE) +#define DriveDirection_DllAPI __declspec( dllexport ) +#else +#define DriveDirection_DllAPI __declspec( dllimport ) +#endif // DriveDirection_SOURCE +#else +#define DriveDirection_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define DriveDirection_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace DriveDirection_Constants { + const uint8_t FORWARD = 0; + const uint8_t BACKWARD = 1; + const uint8_t UNAVAILABLE = 2; + } // namespace DriveDirection_Constants + /*! + * @brief This class represents the structure DriveDirection defined by the user in the IDL file. + * @ingroup DRIVEDIRECTION + */ + class DriveDirection + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport DriveDirection(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~DriveDirection(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::DriveDirection that will be copied. + */ + eProsima_user_DllExport DriveDirection( + const DriveDirection& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::DriveDirection that will be copied. + */ + eProsima_user_DllExport DriveDirection( + DriveDirection&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::DriveDirection that will be copied. + */ + eProsima_user_DllExport DriveDirection& operator =( + const DriveDirection& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::DriveDirection that will be copied. + */ + eProsima_user_DllExport DriveDirection& operator =( + DriveDirection&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::DriveDirection object to compare. + */ + eProsima_user_DllExport bool operator ==( + const DriveDirection& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::DriveDirection object to compare. + */ + eProsima_user_DllExport bool operator !=( + const DriveDirection& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::DriveDirection& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVEDIRECTION_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirectionPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirectionPubSubTypes.cxx new file mode 100644 index 00000000000..7783faf2982 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirectionPubSubTypes.cxx @@ -0,0 +1,182 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DriveDirectionPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "DriveDirectionPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace DriveDirection_Constants { + + + + + } //End of namespace DriveDirection_Constants + DriveDirectionPubSubType::DriveDirectionPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::DriveDirection_"); + auto type_size = DriveDirection::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = DriveDirection::isKeyDefined(); + size_t keyLength = DriveDirection::getKeyMaxCdrSerializedSize() > 16 ? + DriveDirection::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + DriveDirectionPubSubType::~DriveDirectionPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool DriveDirectionPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + DriveDirection* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool DriveDirectionPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + DriveDirection* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function DriveDirectionPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* DriveDirectionPubSubType::createData() + { + return reinterpret_cast(new DriveDirection()); + } + + void DriveDirectionPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool DriveDirectionPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + DriveDirection* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + DriveDirection::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || DriveDirection::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirectionPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirectionPubSubTypes.h new file mode 100644 index 00000000000..2f76ff111fe --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirectionPubSubTypes.h @@ -0,0 +1,113 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DriveDirectionPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVEDIRECTION_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVEDIRECTION_PUBSUBTYPES_H_ + +#include +#include + +#include "DriveDirection.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated DriveDirection is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace DriveDirection_Constants + { + + + + } + /*! + * @brief This class represents the TopicDataType of the type DriveDirection defined by the user in the IDL file. + * @ingroup DRIVEDIRECTION + */ + class DriveDirectionPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef DriveDirection type; + + eProsima_user_DllExport DriveDirectionPubSubType(); + + eProsima_user_DllExport virtual ~DriveDirectionPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) DriveDirection(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVEDIRECTION_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatus.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatus.cxx new file mode 100644 index 00000000000..0daf5932cc6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatus.cxx @@ -0,0 +1,249 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DrivingLaneStatus.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "DrivingLaneStatus.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + +etsi_its_cam_msgs::msg::DrivingLaneStatus::DrivingLaneStatus() +{ + // m_value com.eprosima.idl.parser.typecode.SequenceTypeCode@15a902e7 + + // m_bits_unused com.eprosima.idl.parser.typecode.PrimitiveTypeCode@7876d598 + m_bits_unused = 0; + +} + +etsi_its_cam_msgs::msg::DrivingLaneStatus::~DrivingLaneStatus() +{ + +} + +etsi_its_cam_msgs::msg::DrivingLaneStatus::DrivingLaneStatus( + const DrivingLaneStatus& x) +{ + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; +} + +etsi_its_cam_msgs::msg::DrivingLaneStatus::DrivingLaneStatus( + DrivingLaneStatus&& x) +{ + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; +} + +etsi_its_cam_msgs::msg::DrivingLaneStatus& etsi_its_cam_msgs::msg::DrivingLaneStatus::operator =( + const DrivingLaneStatus& x) +{ + + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; + + return *this; +} + +etsi_its_cam_msgs::msg::DrivingLaneStatus& etsi_its_cam_msgs::msg::DrivingLaneStatus::operator =( + DrivingLaneStatus&& x) +{ + + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; + + return *this; +} + +bool etsi_its_cam_msgs::msg::DrivingLaneStatus::operator ==( + const DrivingLaneStatus& x) const +{ + + return (m_value == x.m_value && m_bits_unused == x.m_bits_unused); +} + +bool etsi_its_cam_msgs::msg::DrivingLaneStatus::operator !=( + const DrivingLaneStatus& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::DrivingLaneStatus::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + current_alignment += (100 * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::DrivingLaneStatus::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::DrivingLaneStatus& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + if (data.value().size() > 0) + { + current_alignment += (data.value().size() * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + } + + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::DrivingLaneStatus::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + scdr << m_bits_unused; + +} + +void etsi_its_cam_msgs::msg::DrivingLaneStatus::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; + dcdr >> m_bits_unused; +} + +/*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ +void etsi_its_cam_msgs::msg::DrivingLaneStatus::value( + const std::vector& _value) +{ + m_value = _value; +} + +/*! + * @brief This function moves the value in member value + * @param _value New value to be moved in member value + */ +void etsi_its_cam_msgs::msg::DrivingLaneStatus::value( + std::vector&& _value) +{ + m_value = std::move(_value); +} + +/*! + * @brief This function returns a constant reference to member value + * @return Constant reference to member value + */ +const std::vector& etsi_its_cam_msgs::msg::DrivingLaneStatus::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +std::vector& etsi_its_cam_msgs::msg::DrivingLaneStatus::value() +{ + return m_value; +} +/*! + * @brief This function sets a value in member bits_unused + * @param _bits_unused New value for member bits_unused + */ +void etsi_its_cam_msgs::msg::DrivingLaneStatus::bits_unused( + uint8_t _bits_unused) +{ + m_bits_unused = _bits_unused; +} + +/*! + * @brief This function returns the value of member bits_unused + * @return Value of member bits_unused + */ +uint8_t etsi_its_cam_msgs::msg::DrivingLaneStatus::bits_unused() const +{ + return m_bits_unused; +} + +/*! + * @brief This function returns a reference to member bits_unused + * @return Reference to member bits_unused + */ +uint8_t& etsi_its_cam_msgs::msg::DrivingLaneStatus::bits_unused() +{ + return m_bits_unused; +} + + +size_t etsi_its_cam_msgs::msg::DrivingLaneStatus::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::DrivingLaneStatus::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::DrivingLaneStatus::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatus.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatus.h new file mode 100644 index 00000000000..13f818ad751 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatus.h @@ -0,0 +1,240 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DrivingLaneStatus.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVINGLANESTATUS_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVINGLANESTATUS_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(DrivingLaneStatus_SOURCE) +#define DrivingLaneStatus_DllAPI __declspec( dllexport ) +#else +#define DrivingLaneStatus_DllAPI __declspec( dllimport ) +#endif // DrivingLaneStatus_SOURCE +#else +#define DrivingLaneStatus_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define DrivingLaneStatus_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace DrivingLaneStatus_Constants { + const uint8_t MIN_SIZE_BITS = 1; + const uint8_t MAX_SIZE_BITS = 13; + } // namespace DrivingLaneStatus_Constants + /*! + * @brief This class represents the structure DrivingLaneStatus defined by the user in the IDL file. + * @ingroup DRIVINGLANESTATUS + */ + class DrivingLaneStatus + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport DrivingLaneStatus(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~DrivingLaneStatus(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::DrivingLaneStatus that will be copied. + */ + eProsima_user_DllExport DrivingLaneStatus( + const DrivingLaneStatus& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::DrivingLaneStatus that will be copied. + */ + eProsima_user_DllExport DrivingLaneStatus( + DrivingLaneStatus&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::DrivingLaneStatus that will be copied. + */ + eProsima_user_DllExport DrivingLaneStatus& operator =( + const DrivingLaneStatus& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::DrivingLaneStatus that will be copied. + */ + eProsima_user_DllExport DrivingLaneStatus& operator =( + DrivingLaneStatus&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::DrivingLaneStatus object to compare. + */ + eProsima_user_DllExport bool operator ==( + const DrivingLaneStatus& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::DrivingLaneStatus object to compare. + */ + eProsima_user_DllExport bool operator !=( + const DrivingLaneStatus& x) const; + + /*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ + eProsima_user_DllExport void value( + const std::vector& _value); + + /*! + * @brief This function moves the value in member value + * @param _value New value to be moved in member value + */ + eProsima_user_DllExport void value( + std::vector&& _value); + + /*! + * @brief This function returns a constant reference to member value + * @return Constant reference to member value + */ + eProsima_user_DllExport const std::vector& value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport std::vector& value(); + /*! + * @brief This function sets a value in member bits_unused + * @param _bits_unused New value for member bits_unused + */ + eProsima_user_DllExport void bits_unused( + uint8_t _bits_unused); + + /*! + * @brief This function returns the value of member bits_unused + * @return Value of member bits_unused + */ + eProsima_user_DllExport uint8_t bits_unused() const; + + /*! + * @brief This function returns a reference to member bits_unused + * @return Reference to member bits_unused + */ + eProsima_user_DllExport uint8_t& bits_unused(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::DrivingLaneStatus& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std::vector m_value; + uint8_t m_bits_unused; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVINGLANESTATUS_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatusPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatusPubSubTypes.cxx new file mode 100644 index 00000000000..88981d7a021 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatusPubSubTypes.cxx @@ -0,0 +1,181 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file DrivingLaneStatusPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "DrivingLaneStatusPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace DrivingLaneStatus_Constants { + + + + } //End of namespace DrivingLaneStatus_Constants + DrivingLaneStatusPubSubType::DrivingLaneStatusPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::DrivingLaneStatus_"); + auto type_size = DrivingLaneStatus::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = DrivingLaneStatus::isKeyDefined(); + size_t keyLength = DrivingLaneStatus::getKeyMaxCdrSerializedSize() > 16 ? + DrivingLaneStatus::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + DrivingLaneStatusPubSubType::~DrivingLaneStatusPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool DrivingLaneStatusPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + DrivingLaneStatus* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool DrivingLaneStatusPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + DrivingLaneStatus* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function DrivingLaneStatusPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* DrivingLaneStatusPubSubType::createData() + { + return reinterpret_cast(new DrivingLaneStatus()); + } + + void DrivingLaneStatusPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool DrivingLaneStatusPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + DrivingLaneStatus* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + DrivingLaneStatus::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || DrivingLaneStatus::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/types/CarlaLineInvasionPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatusPubSubTypes.h similarity index 77% rename from LibCarla/source/carla/ros2/types/CarlaLineInvasionPubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatusPubSubTypes.h index a735ff75839..7cdb201e61a 100644 --- a/LibCarla/source/carla/ros2/types/CarlaLineInvasionPubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatusPubSubTypes.h @@ -13,42 +13,48 @@ // limitations under the License. /*! - * @file CarlaLineInvasionPubSubTypes.h + * @file DrivingLaneStatusPubSubTypes.h * This header file contains the declaration of the serialization functions. * * This file was generated by the tool fastcdrgen. */ -#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALINEINVASION_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALINEINVASION_PUBSUBTYPES_H_ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVINGLANESTATUS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVINGLANESTATUS_PUBSUBTYPES_H_ #include #include -#include "CarlaLineInvasion.h" -#include "HeaderPubSubTypes.h" +#include "DrivingLaneStatus.h" #if !defined(GEN_API_VER) || (GEN_API_VER != 1) #error \ - Generated CarlaLineInvasion is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. + Generated DrivingLaneStatus is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. #endif // GEN_API_VER -namespace carla_msgs +namespace etsi_its_cam_msgs { namespace msg { + namespace DrivingLaneStatus_Constants + { + + + } /*! - * @brief This class represents the TopicDataType of the type LaneInvasionEvent defined by the user in the IDL file. - * @ingroup CARLALINEINVASION + * @brief This class represents the TopicDataType of the type DrivingLaneStatus defined by the user in the IDL file. + * @ingroup DRIVINGLANESTATUS */ - class LaneInvasionEventPubSubType : public eprosima::fastdds::dds::TopicDataType + class DrivingLaneStatusPubSubType : public eprosima::fastdds::dds::TopicDataType { public: - typedef LaneInvasionEvent type; - eProsima_user_DllExport LaneInvasionEventPubSubType(); + typedef DrivingLaneStatus type; + + eProsima_user_DllExport DrivingLaneStatusPubSubType(); - eProsima_user_DllExport virtual ~LaneInvasionEventPubSubType() override; + eProsima_user_DllExport virtual ~DrivingLaneStatusPubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -96,10 +102,11 @@ namespace carla_msgs } #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; unsigned char* m_keyBuffer; }; } } -#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALINEINVASION_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVINGLANESTATUS_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatus.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatus.cxx new file mode 100644 index 00000000000..474bdbeac78 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatus.cxx @@ -0,0 +1,183 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file EmbarkationStatus.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "EmbarkationStatus.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::EmbarkationStatus::EmbarkationStatus() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@4de025bf + m_value = false; + +} + +etsi_its_cam_msgs::msg::EmbarkationStatus::~EmbarkationStatus() +{ +} + +etsi_its_cam_msgs::msg::EmbarkationStatus::EmbarkationStatus( + const EmbarkationStatus& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::EmbarkationStatus::EmbarkationStatus( + EmbarkationStatus&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::EmbarkationStatus& etsi_its_cam_msgs::msg::EmbarkationStatus::operator =( + const EmbarkationStatus& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::EmbarkationStatus& etsi_its_cam_msgs::msg::EmbarkationStatus::operator =( + EmbarkationStatus&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::EmbarkationStatus::operator ==( + const EmbarkationStatus& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::EmbarkationStatus::operator !=( + const EmbarkationStatus& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::EmbarkationStatus::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::EmbarkationStatus::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::EmbarkationStatus& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::EmbarkationStatus::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::EmbarkationStatus::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::EmbarkationStatus::value( + bool _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +bool etsi_its_cam_msgs::msg::EmbarkationStatus::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +bool& etsi_its_cam_msgs::msg::EmbarkationStatus::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::EmbarkationStatus::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::EmbarkationStatus::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::EmbarkationStatus::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatus.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatus.h new file mode 100644 index 00000000000..fefe2a1836c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatus.h @@ -0,0 +1,210 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file EmbarkationStatus.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMBARKATIONSTATUS_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMBARKATIONSTATUS_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(EmbarkationStatus_SOURCE) +#define EmbarkationStatus_DllAPI __declspec( dllexport ) +#else +#define EmbarkationStatus_DllAPI __declspec( dllimport ) +#endif // EmbarkationStatus_SOURCE +#else +#define EmbarkationStatus_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define EmbarkationStatus_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure EmbarkationStatus defined by the user in the IDL file. + * @ingroup EMBARKATIONSTATUS + */ + class EmbarkationStatus + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport EmbarkationStatus(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~EmbarkationStatus(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::EmbarkationStatus that will be copied. + */ + eProsima_user_DllExport EmbarkationStatus( + const EmbarkationStatus& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::EmbarkationStatus that will be copied. + */ + eProsima_user_DllExport EmbarkationStatus( + EmbarkationStatus&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::EmbarkationStatus that will be copied. + */ + eProsima_user_DllExport EmbarkationStatus& operator =( + const EmbarkationStatus& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::EmbarkationStatus that will be copied. + */ + eProsima_user_DllExport EmbarkationStatus& operator =( + EmbarkationStatus&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::EmbarkationStatus object to compare. + */ + eProsima_user_DllExport bool operator ==( + const EmbarkationStatus& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::EmbarkationStatus object to compare. + */ + eProsima_user_DllExport bool operator !=( + const EmbarkationStatus& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + bool _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport bool value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport bool& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::EmbarkationStatus& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + bool m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMBARKATIONSTATUS_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatusPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatusPubSubTypes.cxx new file mode 100644 index 00000000000..d44e6b7a559 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatusPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file EmbarkationStatusPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "EmbarkationStatusPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + EmbarkationStatusPubSubType::EmbarkationStatusPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::EmbarkationStatus_"); + auto type_size = EmbarkationStatus::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = EmbarkationStatus::isKeyDefined(); + size_t keyLength = EmbarkationStatus::getKeyMaxCdrSerializedSize() > 16 ? + EmbarkationStatus::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + EmbarkationStatusPubSubType::~EmbarkationStatusPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool EmbarkationStatusPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + EmbarkationStatus* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool EmbarkationStatusPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + EmbarkationStatus* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function EmbarkationStatusPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* EmbarkationStatusPubSubType::createData() + { + return reinterpret_cast(new EmbarkationStatus()); + } + + void EmbarkationStatusPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool EmbarkationStatusPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + EmbarkationStatus* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + EmbarkationStatus::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || EmbarkationStatus::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatusPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatusPubSubTypes.h new file mode 100644 index 00000000000..c5197616663 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatusPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file EmbarkationStatusPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMBARKATIONSTATUS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMBARKATIONSTATUS_PUBSUBTYPES_H_ + +#include +#include + +#include "EmbarkationStatus.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated EmbarkationStatus is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type EmbarkationStatus defined by the user in the IDL file. + * @ingroup EMBARKATIONSTATUS + */ + class EmbarkationStatusPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef EmbarkationStatus type; + + eProsima_user_DllExport EmbarkationStatusPubSubType(); + + eProsima_user_DllExport virtual ~EmbarkationStatusPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) EmbarkationStatus(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMBARKATIONSTATUS_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainer.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainer.cxx new file mode 100644 index 00000000000..10d5e7a80e7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainer.cxx @@ -0,0 +1,372 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file EmergencyContainer.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "EmergencyContainer.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::EmergencyContainer::EmergencyContainer() +{ + // m_light_bar_siren_in_use com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@182f1e9a + + // m_incident_indication com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@6928f576 + + // m_incident_indication_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@660e9100 + m_incident_indication_is_present = false; + // m_emergency_priority com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@69f63d95 + + // m_emergency_priority_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@9cd25ff + m_emergency_priority_is_present = false; + +} + +etsi_its_cam_msgs::msg::EmergencyContainer::~EmergencyContainer() +{ + + + + +} + +etsi_its_cam_msgs::msg::EmergencyContainer::EmergencyContainer( + const EmergencyContainer& x) +{ + m_light_bar_siren_in_use = x.m_light_bar_siren_in_use; + m_incident_indication = x.m_incident_indication; + m_incident_indication_is_present = x.m_incident_indication_is_present; + m_emergency_priority = x.m_emergency_priority; + m_emergency_priority_is_present = x.m_emergency_priority_is_present; +} + +etsi_its_cam_msgs::msg::EmergencyContainer::EmergencyContainer( + EmergencyContainer&& x) +{ + m_light_bar_siren_in_use = std::move(x.m_light_bar_siren_in_use); + m_incident_indication = std::move(x.m_incident_indication); + m_incident_indication_is_present = x.m_incident_indication_is_present; + m_emergency_priority = std::move(x.m_emergency_priority); + m_emergency_priority_is_present = x.m_emergency_priority_is_present; +} + +etsi_its_cam_msgs::msg::EmergencyContainer& etsi_its_cam_msgs::msg::EmergencyContainer::operator =( + const EmergencyContainer& x) +{ + + m_light_bar_siren_in_use = x.m_light_bar_siren_in_use; + m_incident_indication = x.m_incident_indication; + m_incident_indication_is_present = x.m_incident_indication_is_present; + m_emergency_priority = x.m_emergency_priority; + m_emergency_priority_is_present = x.m_emergency_priority_is_present; + + return *this; +} + +etsi_its_cam_msgs::msg::EmergencyContainer& etsi_its_cam_msgs::msg::EmergencyContainer::operator =( + EmergencyContainer&& x) +{ + + m_light_bar_siren_in_use = std::move(x.m_light_bar_siren_in_use); + m_incident_indication = std::move(x.m_incident_indication); + m_incident_indication_is_present = x.m_incident_indication_is_present; + m_emergency_priority = std::move(x.m_emergency_priority); + m_emergency_priority_is_present = x.m_emergency_priority_is_present; + + return *this; +} + +bool etsi_its_cam_msgs::msg::EmergencyContainer::operator ==( + const EmergencyContainer& x) const +{ + + return (m_light_bar_siren_in_use == x.m_light_bar_siren_in_use && m_incident_indication == x.m_incident_indication && m_incident_indication_is_present == x.m_incident_indication_is_present && m_emergency_priority == x.m_emergency_priority && m_emergency_priority_is_present == x.m_emergency_priority_is_present); +} + +bool etsi_its_cam_msgs::msg::EmergencyContainer::operator !=( + const EmergencyContainer& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::EmergencyContainer::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::LightBarSirenInUse::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::CauseCode::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::EmergencyPriority::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::EmergencyContainer::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::EmergencyContainer& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::LightBarSirenInUse::getCdrSerializedSize(data.light_bar_siren_in_use(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::CauseCode::getCdrSerializedSize(data.incident_indication(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::EmergencyPriority::getCdrSerializedSize(data.emergency_priority(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::EmergencyContainer::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_light_bar_siren_in_use; + scdr << m_incident_indication; + scdr << m_incident_indication_is_present; + scdr << m_emergency_priority; + scdr << m_emergency_priority_is_present; + +} + +void etsi_its_cam_msgs::msg::EmergencyContainer::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_light_bar_siren_in_use; + dcdr >> m_incident_indication; + dcdr >> m_incident_indication_is_present; + dcdr >> m_emergency_priority; + dcdr >> m_emergency_priority_is_present; +} + +/*! + * @brief This function copies the value in member light_bar_siren_in_use + * @param _light_bar_siren_in_use New value to be copied in member light_bar_siren_in_use + */ +void etsi_its_cam_msgs::msg::EmergencyContainer::light_bar_siren_in_use( + const etsi_its_cam_msgs::msg::LightBarSirenInUse& _light_bar_siren_in_use) +{ + m_light_bar_siren_in_use = _light_bar_siren_in_use; +} + +/*! + * @brief This function moves the value in member light_bar_siren_in_use + * @param _light_bar_siren_in_use New value to be moved in member light_bar_siren_in_use + */ +void etsi_its_cam_msgs::msg::EmergencyContainer::light_bar_siren_in_use( + etsi_its_cam_msgs::msg::LightBarSirenInUse&& _light_bar_siren_in_use) +{ + m_light_bar_siren_in_use = std::move(_light_bar_siren_in_use); +} + +/*! + * @brief This function returns a constant reference to member light_bar_siren_in_use + * @return Constant reference to member light_bar_siren_in_use + */ +const etsi_its_cam_msgs::msg::LightBarSirenInUse& etsi_its_cam_msgs::msg::EmergencyContainer::light_bar_siren_in_use() const +{ + return m_light_bar_siren_in_use; +} + +/*! + * @brief This function returns a reference to member light_bar_siren_in_use + * @return Reference to member light_bar_siren_in_use + */ +etsi_its_cam_msgs::msg::LightBarSirenInUse& etsi_its_cam_msgs::msg::EmergencyContainer::light_bar_siren_in_use() +{ + return m_light_bar_siren_in_use; +} +/*! + * @brief This function copies the value in member incident_indication + * @param _incident_indication New value to be copied in member incident_indication + */ +void etsi_its_cam_msgs::msg::EmergencyContainer::incident_indication( + const etsi_its_cam_msgs::msg::CauseCode& _incident_indication) +{ + m_incident_indication = _incident_indication; +} + +/*! + * @brief This function moves the value in member incident_indication + * @param _incident_indication New value to be moved in member incident_indication + */ +void etsi_its_cam_msgs::msg::EmergencyContainer::incident_indication( + etsi_its_cam_msgs::msg::CauseCode&& _incident_indication) +{ + m_incident_indication = std::move(_incident_indication); +} + +/*! + * @brief This function returns a constant reference to member incident_indication + * @return Constant reference to member incident_indication + */ +const etsi_its_cam_msgs::msg::CauseCode& etsi_its_cam_msgs::msg::EmergencyContainer::incident_indication() const +{ + return m_incident_indication; +} + +/*! + * @brief This function returns a reference to member incident_indication + * @return Reference to member incident_indication + */ +etsi_its_cam_msgs::msg::CauseCode& etsi_its_cam_msgs::msg::EmergencyContainer::incident_indication() +{ + return m_incident_indication; +} +/*! + * @brief This function sets a value in member incident_indication_is_present + * @param _incident_indication_is_present New value for member incident_indication_is_present + */ +void etsi_its_cam_msgs::msg::EmergencyContainer::incident_indication_is_present( + bool _incident_indication_is_present) +{ + m_incident_indication_is_present = _incident_indication_is_present; +} + +/*! + * @brief This function returns the value of member incident_indication_is_present + * @return Value of member incident_indication_is_present + */ +bool etsi_its_cam_msgs::msg::EmergencyContainer::incident_indication_is_present() const +{ + return m_incident_indication_is_present; +} + +/*! + * @brief This function returns a reference to member incident_indication_is_present + * @return Reference to member incident_indication_is_present + */ +bool& etsi_its_cam_msgs::msg::EmergencyContainer::incident_indication_is_present() +{ + return m_incident_indication_is_present; +} + +/*! + * @brief This function copies the value in member emergency_priority + * @param _emergency_priority New value to be copied in member emergency_priority + */ +void etsi_its_cam_msgs::msg::EmergencyContainer::emergency_priority( + const etsi_its_cam_msgs::msg::EmergencyPriority& _emergency_priority) +{ + m_emergency_priority = _emergency_priority; +} + +/*! + * @brief This function moves the value in member emergency_priority + * @param _emergency_priority New value to be moved in member emergency_priority + */ +void etsi_its_cam_msgs::msg::EmergencyContainer::emergency_priority( + etsi_its_cam_msgs::msg::EmergencyPriority&& _emergency_priority) +{ + m_emergency_priority = std::move(_emergency_priority); +} + +/*! + * @brief This function returns a constant reference to member emergency_priority + * @return Constant reference to member emergency_priority + */ +const etsi_its_cam_msgs::msg::EmergencyPriority& etsi_its_cam_msgs::msg::EmergencyContainer::emergency_priority() const +{ + return m_emergency_priority; +} + +/*! + * @brief This function returns a reference to member emergency_priority + * @return Reference to member emergency_priority + */ +etsi_its_cam_msgs::msg::EmergencyPriority& etsi_its_cam_msgs::msg::EmergencyContainer::emergency_priority() +{ + return m_emergency_priority; +} +/*! + * @brief This function sets a value in member emergency_priority_is_present + * @param _emergency_priority_is_present New value for member emergency_priority_is_present + */ +void etsi_its_cam_msgs::msg::EmergencyContainer::emergency_priority_is_present( + bool _emergency_priority_is_present) +{ + m_emergency_priority_is_present = _emergency_priority_is_present; +} + +/*! + * @brief This function returns the value of member emergency_priority_is_present + * @return Value of member emergency_priority_is_present + */ +bool etsi_its_cam_msgs::msg::EmergencyContainer::emergency_priority_is_present() const +{ + return m_emergency_priority_is_present; +} + +/*! + * @brief This function returns a reference to member emergency_priority_is_present + * @return Reference to member emergency_priority_is_present + */ +bool& etsi_its_cam_msgs::msg::EmergencyContainer::emergency_priority_is_present() +{ + return m_emergency_priority_is_present; +} + + +size_t etsi_its_cam_msgs::msg::EmergencyContainer::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::EmergencyContainer::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::EmergencyContainer::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainer.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainer.h new file mode 100644 index 00000000000..ac0796f9349 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainer.h @@ -0,0 +1,311 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file EmergencyContainer.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYCONTAINER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYCONTAINER_H_ + +#include "CauseCode.h" +#include "EmergencyPriority.h" +#include "LightBarSirenInUse.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(EmergencyContainer_SOURCE) +#define EmergencyContainer_DllAPI __declspec( dllexport ) +#else +#define EmergencyContainer_DllAPI __declspec( dllimport ) +#endif // EmergencyContainer_SOURCE +#else +#define EmergencyContainer_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define EmergencyContainer_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure EmergencyContainer defined by the user in the IDL file. + * @ingroup EMERGENCYCONTAINER + */ + class EmergencyContainer + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport EmergencyContainer(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~EmergencyContainer(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::EmergencyContainer that will be copied. + */ + eProsima_user_DllExport EmergencyContainer( + const EmergencyContainer& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::EmergencyContainer that will be copied. + */ + eProsima_user_DllExport EmergencyContainer( + EmergencyContainer&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::EmergencyContainer that will be copied. + */ + eProsima_user_DllExport EmergencyContainer& operator =( + const EmergencyContainer& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::EmergencyContainer that will be copied. + */ + eProsima_user_DllExport EmergencyContainer& operator =( + EmergencyContainer&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::EmergencyContainer object to compare. + */ + eProsima_user_DllExport bool operator ==( + const EmergencyContainer& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::EmergencyContainer object to compare. + */ + eProsima_user_DllExport bool operator !=( + const EmergencyContainer& x) const; + + /*! + * @brief This function copies the value in member light_bar_siren_in_use + * @param _light_bar_siren_in_use New value to be copied in member light_bar_siren_in_use + */ + eProsima_user_DllExport void light_bar_siren_in_use( + const etsi_its_cam_msgs::msg::LightBarSirenInUse& _light_bar_siren_in_use); + + /*! + * @brief This function moves the value in member light_bar_siren_in_use + * @param _light_bar_siren_in_use New value to be moved in member light_bar_siren_in_use + */ + eProsima_user_DllExport void light_bar_siren_in_use( + etsi_its_cam_msgs::msg::LightBarSirenInUse&& _light_bar_siren_in_use); + + /*! + * @brief This function returns a constant reference to member light_bar_siren_in_use + * @return Constant reference to member light_bar_siren_in_use + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::LightBarSirenInUse& light_bar_siren_in_use() const; + + /*! + * @brief This function returns a reference to member light_bar_siren_in_use + * @return Reference to member light_bar_siren_in_use + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::LightBarSirenInUse& light_bar_siren_in_use(); + /*! + * @brief This function copies the value in member incident_indication + * @param _incident_indication New value to be copied in member incident_indication + */ + eProsima_user_DllExport void incident_indication( + const etsi_its_cam_msgs::msg::CauseCode& _incident_indication); + + /*! + * @brief This function moves the value in member incident_indication + * @param _incident_indication New value to be moved in member incident_indication + */ + eProsima_user_DllExport void incident_indication( + etsi_its_cam_msgs::msg::CauseCode&& _incident_indication); + + /*! + * @brief This function returns a constant reference to member incident_indication + * @return Constant reference to member incident_indication + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::CauseCode& incident_indication() const; + + /*! + * @brief This function returns a reference to member incident_indication + * @return Reference to member incident_indication + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::CauseCode& incident_indication(); + /*! + * @brief This function sets a value in member incident_indication_is_present + * @param _incident_indication_is_present New value for member incident_indication_is_present + */ + eProsima_user_DllExport void incident_indication_is_present( + bool _incident_indication_is_present); + + /*! + * @brief This function returns the value of member incident_indication_is_present + * @return Value of member incident_indication_is_present + */ + eProsima_user_DllExport bool incident_indication_is_present() const; + + /*! + * @brief This function returns a reference to member incident_indication_is_present + * @return Reference to member incident_indication_is_present + */ + eProsima_user_DllExport bool& incident_indication_is_present(); + + /*! + * @brief This function copies the value in member emergency_priority + * @param _emergency_priority New value to be copied in member emergency_priority + */ + eProsima_user_DllExport void emergency_priority( + const etsi_its_cam_msgs::msg::EmergencyPriority& _emergency_priority); + + /*! + * @brief This function moves the value in member emergency_priority + * @param _emergency_priority New value to be moved in member emergency_priority + */ + eProsima_user_DllExport void emergency_priority( + etsi_its_cam_msgs::msg::EmergencyPriority&& _emergency_priority); + + /*! + * @brief This function returns a constant reference to member emergency_priority + * @return Constant reference to member emergency_priority + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::EmergencyPriority& emergency_priority() const; + + /*! + * @brief This function returns a reference to member emergency_priority + * @return Reference to member emergency_priority + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::EmergencyPriority& emergency_priority(); + /*! + * @brief This function sets a value in member emergency_priority_is_present + * @param _emergency_priority_is_present New value for member emergency_priority_is_present + */ + eProsima_user_DllExport void emergency_priority_is_present( + bool _emergency_priority_is_present); + + /*! + * @brief This function returns the value of member emergency_priority_is_present + * @return Value of member emergency_priority_is_present + */ + eProsima_user_DllExport bool emergency_priority_is_present() const; + + /*! + * @brief This function returns a reference to member emergency_priority_is_present + * @return Reference to member emergency_priority_is_present + */ + eProsima_user_DllExport bool& emergency_priority_is_present(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::EmergencyContainer& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::LightBarSirenInUse m_light_bar_siren_in_use; + etsi_its_cam_msgs::msg::CauseCode m_incident_indication; + bool m_incident_indication_is_present; + etsi_its_cam_msgs::msg::EmergencyPriority m_emergency_priority; + bool m_emergency_priority_is_present; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYCONTAINER_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainerPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainerPubSubTypes.cxx new file mode 100644 index 00000000000..e5fbe9557bc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainerPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file EmergencyContainerPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "EmergencyContainerPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + EmergencyContainerPubSubType::EmergencyContainerPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::EmergencyContainer_"); + auto type_size = EmergencyContainer::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = EmergencyContainer::isKeyDefined(); + size_t keyLength = EmergencyContainer::getKeyMaxCdrSerializedSize() > 16 ? + EmergencyContainer::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + EmergencyContainerPubSubType::~EmergencyContainerPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool EmergencyContainerPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + EmergencyContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool EmergencyContainerPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + EmergencyContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function EmergencyContainerPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* EmergencyContainerPubSubType::createData() + { + return reinterpret_cast(new EmergencyContainer()); + } + + void EmergencyContainerPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool EmergencyContainerPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + EmergencyContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + EmergencyContainer::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || EmergencyContainer::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainerPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainerPubSubTypes.h new file mode 100644 index 00000000000..d2170db0c27 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainerPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file EmergencyContainerPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYCONTAINER_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYCONTAINER_PUBSUBTYPES_H_ + +#include +#include + +#include "EmergencyContainer.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated EmergencyContainer is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type EmergencyContainer defined by the user in the IDL file. + * @ingroup EMERGENCYCONTAINER + */ + class EmergencyContainerPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef EmergencyContainer type; + + eProsima_user_DllExport EmergencyContainerPubSubType(); + + eProsima_user_DllExport virtual ~EmergencyContainerPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYCONTAINER_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriority.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriority.cxx new file mode 100644 index 00000000000..2a222e75520 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriority.cxx @@ -0,0 +1,250 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file EmergencyPriority.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "EmergencyPriority.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + +etsi_its_cam_msgs::msg::EmergencyPriority::EmergencyPriority() +{ + // m_value com.eprosima.idl.parser.typecode.SequenceTypeCode@579d011c + + // m_bits_unused com.eprosima.idl.parser.typecode.PrimitiveTypeCode@3670f00 + m_bits_unused = 0; + +} + +etsi_its_cam_msgs::msg::EmergencyPriority::~EmergencyPriority() +{ + +} + +etsi_its_cam_msgs::msg::EmergencyPriority::EmergencyPriority( + const EmergencyPriority& x) +{ + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; +} + +etsi_its_cam_msgs::msg::EmergencyPriority::EmergencyPriority( + EmergencyPriority&& x) +{ + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; +} + +etsi_its_cam_msgs::msg::EmergencyPriority& etsi_its_cam_msgs::msg::EmergencyPriority::operator =( + const EmergencyPriority& x) +{ + + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; + + return *this; +} + +etsi_its_cam_msgs::msg::EmergencyPriority& etsi_its_cam_msgs::msg::EmergencyPriority::operator =( + EmergencyPriority&& x) +{ + + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; + + return *this; +} + +bool etsi_its_cam_msgs::msg::EmergencyPriority::operator ==( + const EmergencyPriority& x) const +{ + + return (m_value == x.m_value && m_bits_unused == x.m_bits_unused); +} + +bool etsi_its_cam_msgs::msg::EmergencyPriority::operator !=( + const EmergencyPriority& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::EmergencyPriority::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + current_alignment += (100 * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::EmergencyPriority::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::EmergencyPriority& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + if (data.value().size() > 0) + { + current_alignment += (data.value().size() * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + } + + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::EmergencyPriority::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + scdr << m_bits_unused; + +} + +void etsi_its_cam_msgs::msg::EmergencyPriority::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; + dcdr >> m_bits_unused; +} + +/*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ +void etsi_its_cam_msgs::msg::EmergencyPriority::value( + const std::vector& _value) +{ + m_value = _value; +} + +/*! + * @brief This function moves the value in member value + * @param _value New value to be moved in member value + */ +void etsi_its_cam_msgs::msg::EmergencyPriority::value( + std::vector&& _value) +{ + m_value = std::move(_value); +} + +/*! + * @brief This function returns a constant reference to member value + * @return Constant reference to member value + */ +const std::vector& etsi_its_cam_msgs::msg::EmergencyPriority::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +std::vector& etsi_its_cam_msgs::msg::EmergencyPriority::value() +{ + return m_value; +} +/*! + * @brief This function sets a value in member bits_unused + * @param _bits_unused New value for member bits_unused + */ +void etsi_its_cam_msgs::msg::EmergencyPriority::bits_unused( + uint8_t _bits_unused) +{ + m_bits_unused = _bits_unused; +} + +/*! + * @brief This function returns the value of member bits_unused + * @return Value of member bits_unused + */ +uint8_t etsi_its_cam_msgs::msg::EmergencyPriority::bits_unused() const +{ + return m_bits_unused; +} + +/*! + * @brief This function returns a reference to member bits_unused + * @return Reference to member bits_unused + */ +uint8_t& etsi_its_cam_msgs::msg::EmergencyPriority::bits_unused() +{ + return m_bits_unused; +} + + +size_t etsi_its_cam_msgs::msg::EmergencyPriority::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::EmergencyPriority::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::EmergencyPriority::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriority.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriority.h new file mode 100644 index 00000000000..bd680728921 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriority.h @@ -0,0 +1,241 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file EmergencyPriority.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYPRIORITY_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYPRIORITY_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(EmergencyPriority_SOURCE) +#define EmergencyPriority_DllAPI __declspec( dllexport ) +#else +#define EmergencyPriority_DllAPI __declspec( dllimport ) +#endif // EmergencyPriority_SOURCE +#else +#define EmergencyPriority_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define EmergencyPriority_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace EmergencyPriority_Constants { + const uint8_t SIZE_BITS = 2; + const uint8_t BIT_INDEX_REQUEST_FOR_RIGHT_OF_WAY = 0; + const uint8_t BIT_INDEX_REQUEST_FOR_FREE_CROSSING_AT_A_TRAFFIC_LIGHT = 1; + } // namespace EmergencyPriority_Constants + /*! + * @brief This class represents the structure EmergencyPriority defined by the user in the IDL file. + * @ingroup EMERGENCYPRIORITY + */ + class EmergencyPriority + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport EmergencyPriority(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~EmergencyPriority(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::EmergencyPriority that will be copied. + */ + eProsima_user_DllExport EmergencyPriority( + const EmergencyPriority& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::EmergencyPriority that will be copied. + */ + eProsima_user_DllExport EmergencyPriority( + EmergencyPriority&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::EmergencyPriority that will be copied. + */ + eProsima_user_DllExport EmergencyPriority& operator =( + const EmergencyPriority& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::EmergencyPriority that will be copied. + */ + eProsima_user_DllExport EmergencyPriority& operator =( + EmergencyPriority&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::EmergencyPriority object to compare. + */ + eProsima_user_DllExport bool operator ==( + const EmergencyPriority& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::EmergencyPriority object to compare. + */ + eProsima_user_DllExport bool operator !=( + const EmergencyPriority& x) const; + + /*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ + eProsima_user_DllExport void value( + const std::vector& _value); + + /*! + * @brief This function moves the value in member value + * @param _value New value to be moved in member value + */ + eProsima_user_DllExport void value( + std::vector&& _value); + + /*! + * @brief This function returns a constant reference to member value + * @return Constant reference to member value + */ + eProsima_user_DllExport const std::vector& value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport std::vector& value(); + /*! + * @brief This function sets a value in member bits_unused + * @param _bits_unused New value for member bits_unused + */ + eProsima_user_DllExport void bits_unused( + uint8_t _bits_unused); + + /*! + * @brief This function returns the value of member bits_unused + * @return Value of member bits_unused + */ + eProsima_user_DllExport uint8_t bits_unused() const; + + /*! + * @brief This function returns a reference to member bits_unused + * @return Reference to member bits_unused + */ + eProsima_user_DllExport uint8_t& bits_unused(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::EmergencyPriority& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std::vector m_value; + uint8_t m_bits_unused; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYPRIORITY_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriorityPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriorityPubSubTypes.cxx new file mode 100644 index 00000000000..4e446121723 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriorityPubSubTypes.cxx @@ -0,0 +1,182 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file EmergencyPriorityPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "EmergencyPriorityPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace EmergencyPriority_Constants { + + + + + } //End of namespace EmergencyPriority_Constants + EmergencyPriorityPubSubType::EmergencyPriorityPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::EmergencyPriority_"); + auto type_size = EmergencyPriority::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = EmergencyPriority::isKeyDefined(); + size_t keyLength = EmergencyPriority::getKeyMaxCdrSerializedSize() > 16 ? + EmergencyPriority::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + EmergencyPriorityPubSubType::~EmergencyPriorityPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool EmergencyPriorityPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + EmergencyPriority* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool EmergencyPriorityPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + EmergencyPriority* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function EmergencyPriorityPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* EmergencyPriorityPubSubType::createData() + { + return reinterpret_cast(new EmergencyPriority()); + } + + void EmergencyPriorityPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool EmergencyPriorityPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + EmergencyPriority* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + EmergencyPriority::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || EmergencyPriority::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriorityPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriorityPubSubTypes.h new file mode 100644 index 00000000000..8433906892a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriorityPubSubTypes.h @@ -0,0 +1,113 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file EmergencyPriorityPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYPRIORITY_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYPRIORITY_PUBSUBTYPES_H_ + +#include +#include + +#include "EmergencyPriority.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated EmergencyPriority is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace EmergencyPriority_Constants + { + + + + } + /*! + * @brief This class represents the TopicDataType of the type EmergencyPriority defined by the user in the IDL file. + * @ingroup EMERGENCYPRIORITY + */ + class EmergencyPriorityPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef EmergencyPriority type; + + eProsima_user_DllExport EmergencyPriorityPubSubType(); + + eProsima_user_DllExport virtual ~EmergencyPriorityPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYPRIORITY_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLights.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLights.cxx new file mode 100644 index 00000000000..528e147d29c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLights.cxx @@ -0,0 +1,256 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ExteriorLights.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "ExteriorLights.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + + + + +etsi_its_cam_msgs::msg::ExteriorLights::ExteriorLights() +{ + // m_value com.eprosima.idl.parser.typecode.SequenceTypeCode@1a1d3c1a + + // m_bits_unused com.eprosima.idl.parser.typecode.PrimitiveTypeCode@1c65121 + m_bits_unused = 0; + +} + +etsi_its_cam_msgs::msg::ExteriorLights::~ExteriorLights() +{ + +} + +etsi_its_cam_msgs::msg::ExteriorLights::ExteriorLights( + const ExteriorLights& x) +{ + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; +} + +etsi_its_cam_msgs::msg::ExteriorLights::ExteriorLights( + ExteriorLights&& x) +{ + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; +} + +etsi_its_cam_msgs::msg::ExteriorLights& etsi_its_cam_msgs::msg::ExteriorLights::operator =( + const ExteriorLights& x) +{ + + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; + + return *this; +} + +etsi_its_cam_msgs::msg::ExteriorLights& etsi_its_cam_msgs::msg::ExteriorLights::operator =( + ExteriorLights&& x) +{ + + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; + + return *this; +} + +bool etsi_its_cam_msgs::msg::ExteriorLights::operator ==( + const ExteriorLights& x) const +{ + + return (m_value == x.m_value && m_bits_unused == x.m_bits_unused); +} + +bool etsi_its_cam_msgs::msg::ExteriorLights::operator !=( + const ExteriorLights& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::ExteriorLights::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + current_alignment += (100 * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::ExteriorLights::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::ExteriorLights& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + if (data.value().size() > 0) + { + current_alignment += (data.value().size() * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + } + + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::ExteriorLights::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + scdr << m_bits_unused; + +} + +void etsi_its_cam_msgs::msg::ExteriorLights::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; + dcdr >> m_bits_unused; +} + +/*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ +void etsi_its_cam_msgs::msg::ExteriorLights::value( + const std::vector& _value) +{ + m_value = _value; +} + +/*! + * @brief This function moves the value in member value + * @param _value New value to be moved in member value + */ +void etsi_its_cam_msgs::msg::ExteriorLights::value( + std::vector&& _value) +{ + m_value = std::move(_value); +} + +/*! + * @brief This function returns a constant reference to member value + * @return Constant reference to member value + */ +const std::vector& etsi_its_cam_msgs::msg::ExteriorLights::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +std::vector& etsi_its_cam_msgs::msg::ExteriorLights::value() +{ + return m_value; +} +/*! + * @brief This function sets a value in member bits_unused + * @param _bits_unused New value for member bits_unused + */ +void etsi_its_cam_msgs::msg::ExteriorLights::bits_unused( + uint8_t _bits_unused) +{ + m_bits_unused = _bits_unused; +} + +/*! + * @brief This function returns the value of member bits_unused + * @return Value of member bits_unused + */ +uint8_t etsi_its_cam_msgs::msg::ExteriorLights::bits_unused() const +{ + return m_bits_unused; +} + +/*! + * @brief This function returns a reference to member bits_unused + * @return Reference to member bits_unused + */ +uint8_t& etsi_its_cam_msgs::msg::ExteriorLights::bits_unused() +{ + return m_bits_unused; +} + + +size_t etsi_its_cam_msgs::msg::ExteriorLights::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::ExteriorLights::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::ExteriorLights::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLights.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLights.h new file mode 100644 index 00000000000..8e7328dec49 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLights.h @@ -0,0 +1,247 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ExteriorLights.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EXTERIORLIGHTS_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EXTERIORLIGHTS_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(ExteriorLights_SOURCE) +#define ExteriorLights_DllAPI __declspec( dllexport ) +#else +#define ExteriorLights_DllAPI __declspec( dllimport ) +#endif // ExteriorLights_SOURCE +#else +#define ExteriorLights_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define ExteriorLights_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace ExteriorLights_Constants { + const uint8_t SIZE_BITS = 8; + const uint8_t BIT_INDEX_LOW_BEAM_HEADLIGHTS_ON = 0; + const uint8_t BIT_INDEX_HIGH_BEAM_HEADLIGHTS_ON = 1; + const uint8_t BIT_INDEX_LEFT_TURN_SIGNAL_ON = 2; + const uint8_t BIT_INDEX_RIGHT_TURN_SIGNAL_ON = 3; + const uint8_t BIT_INDEX_DAYTIME_RUNNING_LIGHTS_ON = 4; + const uint8_t BIT_INDEX_REVERSE_LIGHT_ON = 5; + const uint8_t BIT_INDEX_FOG_LIGHT_ON = 6; + const uint8_t BIT_INDEX_PARKING_LIGHTS_ON = 7; + } // namespace ExteriorLights_Constants + /*! + * @brief This class represents the structure ExteriorLights defined by the user in the IDL file. + * @ingroup EXTERIORLIGHTS + */ + class ExteriorLights + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport ExteriorLights(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~ExteriorLights(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::ExteriorLights that will be copied. + */ + eProsima_user_DllExport ExteriorLights( + const ExteriorLights& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::ExteriorLights that will be copied. + */ + eProsima_user_DllExport ExteriorLights( + ExteriorLights&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::ExteriorLights that will be copied. + */ + eProsima_user_DllExport ExteriorLights& operator =( + const ExteriorLights& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::ExteriorLights that will be copied. + */ + eProsima_user_DllExport ExteriorLights& operator =( + ExteriorLights&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::ExteriorLights object to compare. + */ + eProsima_user_DllExport bool operator ==( + const ExteriorLights& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::ExteriorLights object to compare. + */ + eProsima_user_DllExport bool operator !=( + const ExteriorLights& x) const; + + /*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ + eProsima_user_DllExport void value( + const std::vector& _value); + + /*! + * @brief This function moves the value in member value + * @param _value New value to be moved in member value + */ + eProsima_user_DllExport void value( + std::vector&& _value); + + /*! + * @brief This function returns a constant reference to member value + * @return Constant reference to member value + */ + eProsima_user_DllExport const std::vector& value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport std::vector& value(); + /*! + * @brief This function sets a value in member bits_unused + * @param _bits_unused New value for member bits_unused + */ + eProsima_user_DllExport void bits_unused( + uint8_t _bits_unused); + + /*! + * @brief This function returns the value of member bits_unused + * @return Value of member bits_unused + */ + eProsima_user_DllExport uint8_t bits_unused() const; + + /*! + * @brief This function returns a reference to member bits_unused + * @return Reference to member bits_unused + */ + eProsima_user_DllExport uint8_t& bits_unused(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::ExteriorLights& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std::vector m_value; + uint8_t m_bits_unused; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EXTERIORLIGHTS_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLightsPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLightsPubSubTypes.cxx new file mode 100644 index 00000000000..08a0205150f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLightsPubSubTypes.cxx @@ -0,0 +1,188 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ExteriorLightsPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "ExteriorLightsPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace ExteriorLights_Constants { + + + + + + + + + + + } //End of namespace ExteriorLights_Constants + ExteriorLightsPubSubType::ExteriorLightsPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::ExteriorLights_"); + auto type_size = ExteriorLights::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = ExteriorLights::isKeyDefined(); + size_t keyLength = ExteriorLights::getKeyMaxCdrSerializedSize() > 16 ? + ExteriorLights::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + ExteriorLightsPubSubType::~ExteriorLightsPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool ExteriorLightsPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + ExteriorLights* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool ExteriorLightsPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + ExteriorLights* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function ExteriorLightsPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* ExteriorLightsPubSubType::createData() + { + return reinterpret_cast(new ExteriorLights()); + } + + void ExteriorLightsPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool ExteriorLightsPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + ExteriorLights* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + ExteriorLights::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || ExteriorLights::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLightsPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLightsPubSubTypes.h new file mode 100644 index 00000000000..9f17312da29 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLightsPubSubTypes.h @@ -0,0 +1,119 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ExteriorLightsPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EXTERIORLIGHTS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EXTERIORLIGHTS_PUBSUBTYPES_H_ + +#include +#include + +#include "ExteriorLights.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated ExteriorLights is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace ExteriorLights_Constants + { + + + + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type ExteriorLights defined by the user in the IDL file. + * @ingroup EXTERIORLIGHTS + */ + class ExteriorLightsPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef ExteriorLights type; + + eProsima_user_DllExport ExteriorLightsPubSubType(); + + eProsima_user_DllExport virtual ~ExteriorLightsPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EXTERIORLIGHTS_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTime.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTime.cxx new file mode 100644 index 00000000000..5297c4ca1ed --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTime.cxx @@ -0,0 +1,187 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file GenerationDeltaTime.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "GenerationDeltaTime.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + +etsi_its_cam_msgs::msg::GenerationDeltaTime::GenerationDeltaTime() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@1c80e49b + m_value = 0; + +} + +etsi_its_cam_msgs::msg::GenerationDeltaTime::~GenerationDeltaTime() +{ +} + +etsi_its_cam_msgs::msg::GenerationDeltaTime::GenerationDeltaTime( + const GenerationDeltaTime& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::GenerationDeltaTime::GenerationDeltaTime( + GenerationDeltaTime&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::GenerationDeltaTime& etsi_its_cam_msgs::msg::GenerationDeltaTime::operator =( + const GenerationDeltaTime& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::GenerationDeltaTime& etsi_its_cam_msgs::msg::GenerationDeltaTime::operator =( + GenerationDeltaTime&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::GenerationDeltaTime::operator ==( + const GenerationDeltaTime& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::GenerationDeltaTime::operator !=( + const GenerationDeltaTime& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::GenerationDeltaTime::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::GenerationDeltaTime::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::GenerationDeltaTime& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::GenerationDeltaTime::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::GenerationDeltaTime::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::GenerationDeltaTime::value( + uint16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint16_t etsi_its_cam_msgs::msg::GenerationDeltaTime::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint16_t& etsi_its_cam_msgs::msg::GenerationDeltaTime::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::GenerationDeltaTime::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::GenerationDeltaTime::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::GenerationDeltaTime::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTime.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTime.h new file mode 100644 index 00000000000..f60dc0d2b54 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTime.h @@ -0,0 +1,215 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file GenerationDeltaTime.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_GENERATIONDELTATIME_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_GENERATIONDELTATIME_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(GenerationDeltaTime_SOURCE) +#define GenerationDeltaTime_DllAPI __declspec( dllexport ) +#else +#define GenerationDeltaTime_DllAPI __declspec( dllimport ) +#endif // GenerationDeltaTime_SOURCE +#else +#define GenerationDeltaTime_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define GenerationDeltaTime_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace GenerationDeltaTime_Constants { + const uint16_t MIN = 0; + const uint16_t MAX = 65535; + const uint16_t ONE_MILLI_SEC = 1; + } // namespace GenerationDeltaTime_Constants + /*! + * @brief This class represents the structure GenerationDeltaTime defined by the user in the IDL file. + * @ingroup GENERATIONDELTATIME + */ + class GenerationDeltaTime + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport GenerationDeltaTime(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~GenerationDeltaTime(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::GenerationDeltaTime that will be copied. + */ + eProsima_user_DllExport GenerationDeltaTime( + const GenerationDeltaTime& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::GenerationDeltaTime that will be copied. + */ + eProsima_user_DllExport GenerationDeltaTime( + GenerationDeltaTime&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::GenerationDeltaTime that will be copied. + */ + eProsima_user_DllExport GenerationDeltaTime& operator =( + const GenerationDeltaTime& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::GenerationDeltaTime that will be copied. + */ + eProsima_user_DllExport GenerationDeltaTime& operator =( + GenerationDeltaTime&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::GenerationDeltaTime object to compare. + */ + eProsima_user_DllExport bool operator ==( + const GenerationDeltaTime& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::GenerationDeltaTime object to compare. + */ + eProsima_user_DllExport bool operator !=( + const GenerationDeltaTime& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint16_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint16_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint16_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::GenerationDeltaTime& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint16_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_GENERATIONDELTATIME_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTimePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTimePubSubTypes.cxx new file mode 100644 index 00000000000..ce2720ba3de --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTimePubSubTypes.cxx @@ -0,0 +1,182 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file GenerationDeltaTimePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "GenerationDeltaTimePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace GenerationDeltaTime_Constants { + + + + + } //End of namespace GenerationDeltaTime_Constants + GenerationDeltaTimePubSubType::GenerationDeltaTimePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::GenerationDeltaTime_"); + auto type_size = GenerationDeltaTime::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = GenerationDeltaTime::isKeyDefined(); + size_t keyLength = GenerationDeltaTime::getKeyMaxCdrSerializedSize() > 16 ? + GenerationDeltaTime::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + GenerationDeltaTimePubSubType::~GenerationDeltaTimePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool GenerationDeltaTimePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + GenerationDeltaTime* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool GenerationDeltaTimePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + GenerationDeltaTime* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function GenerationDeltaTimePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* GenerationDeltaTimePubSubType::createData() + { + return reinterpret_cast(new GenerationDeltaTime()); + } + + void GenerationDeltaTimePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool GenerationDeltaTimePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + GenerationDeltaTime* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + GenerationDeltaTime::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || GenerationDeltaTime::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTimePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTimePubSubTypes.h new file mode 100644 index 00000000000..3cc56e8f5da --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTimePubSubTypes.h @@ -0,0 +1,113 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file GenerationDeltaTimePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_GENERATIONDELTATIME_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_GENERATIONDELTATIME_PUBSUBTYPES_H_ + +#include +#include + +#include "GenerationDeltaTime.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated GenerationDeltaTime is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace GenerationDeltaTime_Constants + { + + + + } + /*! + * @brief This class represents the TopicDataType of the type GenerationDeltaTime defined by the user in the IDL file. + * @ingroup GENERATIONDELTATIME + */ + class GenerationDeltaTimePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef GenerationDeltaTime type; + + eProsima_user_DllExport GenerationDeltaTimePubSubType(); + + eProsima_user_DllExport virtual ~GenerationDeltaTimePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) GenerationDeltaTime(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_GENERATIONDELTATIME_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatus.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatus.cxx new file mode 100644 index 00000000000..b64e21673e6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatus.cxx @@ -0,0 +1,187 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file HardShoulderStatus.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "HardShoulderStatus.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + +etsi_its_cam_msgs::msg::HardShoulderStatus::HardShoulderStatus() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@4b6579e8 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::HardShoulderStatus::~HardShoulderStatus() +{ +} + +etsi_its_cam_msgs::msg::HardShoulderStatus::HardShoulderStatus( + const HardShoulderStatus& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::HardShoulderStatus::HardShoulderStatus( + HardShoulderStatus&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::HardShoulderStatus& etsi_its_cam_msgs::msg::HardShoulderStatus::operator =( + const HardShoulderStatus& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::HardShoulderStatus& etsi_its_cam_msgs::msg::HardShoulderStatus::operator =( + HardShoulderStatus&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::HardShoulderStatus::operator ==( + const HardShoulderStatus& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::HardShoulderStatus::operator !=( + const HardShoulderStatus& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::HardShoulderStatus::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::HardShoulderStatus::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::HardShoulderStatus& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::HardShoulderStatus::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::HardShoulderStatus::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::HardShoulderStatus::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::HardShoulderStatus::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::HardShoulderStatus::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::HardShoulderStatus::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::HardShoulderStatus::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::HardShoulderStatus::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatus.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatus.h new file mode 100644 index 00000000000..074a54f459b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatus.h @@ -0,0 +1,215 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file HardShoulderStatus.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HARDSHOULDERSTATUS_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HARDSHOULDERSTATUS_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(HardShoulderStatus_SOURCE) +#define HardShoulderStatus_DllAPI __declspec( dllexport ) +#else +#define HardShoulderStatus_DllAPI __declspec( dllimport ) +#endif // HardShoulderStatus_SOURCE +#else +#define HardShoulderStatus_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define HardShoulderStatus_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace HardShoulderStatus_Constants { + const uint8_t AVAILABLE_FOR_STOPPING = 0; + const uint8_t CLOSED = 1; + const uint8_t AVAILABLE_FOR_DRIVING = 2; + } // namespace HardShoulderStatus_Constants + /*! + * @brief This class represents the structure HardShoulderStatus defined by the user in the IDL file. + * @ingroup HARDSHOULDERSTATUS + */ + class HardShoulderStatus + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport HardShoulderStatus(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~HardShoulderStatus(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::HardShoulderStatus that will be copied. + */ + eProsima_user_DllExport HardShoulderStatus( + const HardShoulderStatus& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::HardShoulderStatus that will be copied. + */ + eProsima_user_DllExport HardShoulderStatus( + HardShoulderStatus&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::HardShoulderStatus that will be copied. + */ + eProsima_user_DllExport HardShoulderStatus& operator =( + const HardShoulderStatus& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::HardShoulderStatus that will be copied. + */ + eProsima_user_DllExport HardShoulderStatus& operator =( + HardShoulderStatus&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::HardShoulderStatus object to compare. + */ + eProsima_user_DllExport bool operator ==( + const HardShoulderStatus& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::HardShoulderStatus object to compare. + */ + eProsima_user_DllExport bool operator !=( + const HardShoulderStatus& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::HardShoulderStatus& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HARDSHOULDERSTATUS_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatusPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatusPubSubTypes.cxx new file mode 100644 index 00000000000..3dbbade709c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatusPubSubTypes.cxx @@ -0,0 +1,182 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file HardShoulderStatusPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "HardShoulderStatusPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace HardShoulderStatus_Constants { + + + + + } //End of namespace HardShoulderStatus_Constants + HardShoulderStatusPubSubType::HardShoulderStatusPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::HardShoulderStatus_"); + auto type_size = HardShoulderStatus::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = HardShoulderStatus::isKeyDefined(); + size_t keyLength = HardShoulderStatus::getKeyMaxCdrSerializedSize() > 16 ? + HardShoulderStatus::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + HardShoulderStatusPubSubType::~HardShoulderStatusPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool HardShoulderStatusPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + HardShoulderStatus* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool HardShoulderStatusPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + HardShoulderStatus* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function HardShoulderStatusPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* HardShoulderStatusPubSubType::createData() + { + return reinterpret_cast(new HardShoulderStatus()); + } + + void HardShoulderStatusPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool HardShoulderStatusPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + HardShoulderStatus* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + HardShoulderStatus::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || HardShoulderStatus::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatusPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatusPubSubTypes.h new file mode 100644 index 00000000000..e638ab6b0ba --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatusPubSubTypes.h @@ -0,0 +1,113 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file HardShoulderStatusPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HARDSHOULDERSTATUS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HARDSHOULDERSTATUS_PUBSUBTYPES_H_ + +#include +#include + +#include "HardShoulderStatus.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated HardShoulderStatus is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace HardShoulderStatus_Constants + { + + + + } + /*! + * @brief This class represents the TopicDataType of the type HardShoulderStatus defined by the user in the IDL file. + * @ingroup HARDSHOULDERSTATUS + */ + class HardShoulderStatusPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef HardShoulderStatus type; + + eProsima_user_DllExport HardShoulderStatusPubSubType(); + + eProsima_user_DllExport virtual ~HardShoulderStatusPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) HardShoulderStatus(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HARDSHOULDERSTATUS_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Heading.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Heading.cxx new file mode 100644 index 00000000000..752564e14a1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Heading.cxx @@ -0,0 +1,238 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Heading.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Heading.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::Heading::Heading() +{ + // m_heading_value com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@4650a407 + + // m_heading_confidence com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@30135202 + + +} + +etsi_its_cam_msgs::msg::Heading::~Heading() +{ + +} + +etsi_its_cam_msgs::msg::Heading::Heading( + const Heading& x) +{ + m_heading_value = x.m_heading_value; + m_heading_confidence = x.m_heading_confidence; +} + +etsi_its_cam_msgs::msg::Heading::Heading( + Heading&& x) +{ + m_heading_value = std::move(x.m_heading_value); + m_heading_confidence = std::move(x.m_heading_confidence); +} + +etsi_its_cam_msgs::msg::Heading& etsi_its_cam_msgs::msg::Heading::operator =( + const Heading& x) +{ + + m_heading_value = x.m_heading_value; + m_heading_confidence = x.m_heading_confidence; + + return *this; +} + +etsi_its_cam_msgs::msg::Heading& etsi_its_cam_msgs::msg::Heading::operator =( + Heading&& x) +{ + + m_heading_value = std::move(x.m_heading_value); + m_heading_confidence = std::move(x.m_heading_confidence); + + return *this; +} + +bool etsi_its_cam_msgs::msg::Heading::operator ==( + const Heading& x) const +{ + + return (m_heading_value == x.m_heading_value && m_heading_confidence == x.m_heading_confidence); +} + +bool etsi_its_cam_msgs::msg::Heading::operator !=( + const Heading& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::Heading::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::HeadingValue::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::HeadingConfidence::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::Heading::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::Heading& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::HeadingValue::getCdrSerializedSize(data.heading_value(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::HeadingConfidence::getCdrSerializedSize(data.heading_confidence(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::Heading::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_heading_value; + scdr << m_heading_confidence; + +} + +void etsi_its_cam_msgs::msg::Heading::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_heading_value; + dcdr >> m_heading_confidence; +} + +/*! + * @brief This function copies the value in member heading_value + * @param _heading_value New value to be copied in member heading_value + */ +void etsi_its_cam_msgs::msg::Heading::heading_value( + const etsi_its_cam_msgs::msg::HeadingValue& _heading_value) +{ + m_heading_value = _heading_value; +} + +/*! + * @brief This function moves the value in member heading_value + * @param _heading_value New value to be moved in member heading_value + */ +void etsi_its_cam_msgs::msg::Heading::heading_value( + etsi_its_cam_msgs::msg::HeadingValue&& _heading_value) +{ + m_heading_value = std::move(_heading_value); +} + +/*! + * @brief This function returns a constant reference to member heading_value + * @return Constant reference to member heading_value + */ +const etsi_its_cam_msgs::msg::HeadingValue& etsi_its_cam_msgs::msg::Heading::heading_value() const +{ + return m_heading_value; +} + +/*! + * @brief This function returns a reference to member heading_value + * @return Reference to member heading_value + */ +etsi_its_cam_msgs::msg::HeadingValue& etsi_its_cam_msgs::msg::Heading::heading_value() +{ + return m_heading_value; +} +/*! + * @brief This function copies the value in member heading_confidence + * @param _heading_confidence New value to be copied in member heading_confidence + */ +void etsi_its_cam_msgs::msg::Heading::heading_confidence( + const etsi_its_cam_msgs::msg::HeadingConfidence& _heading_confidence) +{ + m_heading_confidence = _heading_confidence; +} + +/*! + * @brief This function moves the value in member heading_confidence + * @param _heading_confidence New value to be moved in member heading_confidence + */ +void etsi_its_cam_msgs::msg::Heading::heading_confidence( + etsi_its_cam_msgs::msg::HeadingConfidence&& _heading_confidence) +{ + m_heading_confidence = std::move(_heading_confidence); +} + +/*! + * @brief This function returns a constant reference to member heading_confidence + * @return Constant reference to member heading_confidence + */ +const etsi_its_cam_msgs::msg::HeadingConfidence& etsi_its_cam_msgs::msg::Heading::heading_confidence() const +{ + return m_heading_confidence; +} + +/*! + * @brief This function returns a reference to member heading_confidence + * @return Reference to member heading_confidence + */ +etsi_its_cam_msgs::msg::HeadingConfidence& etsi_its_cam_msgs::msg::Heading::heading_confidence() +{ + return m_heading_confidence; +} + +size_t etsi_its_cam_msgs::msg::Heading::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::Heading::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::Heading::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Heading.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Heading.h new file mode 100644 index 00000000000..6af346dd677 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Heading.h @@ -0,0 +1,244 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Heading.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADING_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADING_H_ + +#include "HeadingConfidence.h" +#include "HeadingValue.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(Heading_SOURCE) +#define Heading_DllAPI __declspec( dllexport ) +#else +#define Heading_DllAPI __declspec( dllimport ) +#endif // Heading_SOURCE +#else +#define Heading_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define Heading_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure Heading defined by the user in the IDL file. + * @ingroup HEADING + */ + class Heading + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Heading(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Heading(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::Heading that will be copied. + */ + eProsima_user_DllExport Heading( + const Heading& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::Heading that will be copied. + */ + eProsima_user_DllExport Heading( + Heading&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::Heading that will be copied. + */ + eProsima_user_DllExport Heading& operator =( + const Heading& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::Heading that will be copied. + */ + eProsima_user_DllExport Heading& operator =( + Heading&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::Heading object to compare. + */ + eProsima_user_DllExport bool operator ==( + const Heading& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::Heading object to compare. + */ + eProsima_user_DllExport bool operator !=( + const Heading& x) const; + + /*! + * @brief This function copies the value in member heading_value + * @param _heading_value New value to be copied in member heading_value + */ + eProsima_user_DllExport void heading_value( + const etsi_its_cam_msgs::msg::HeadingValue& _heading_value); + + /*! + * @brief This function moves the value in member heading_value + * @param _heading_value New value to be moved in member heading_value + */ + eProsima_user_DllExport void heading_value( + etsi_its_cam_msgs::msg::HeadingValue&& _heading_value); + + /*! + * @brief This function returns a constant reference to member heading_value + * @return Constant reference to member heading_value + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::HeadingValue& heading_value() const; + + /*! + * @brief This function returns a reference to member heading_value + * @return Reference to member heading_value + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::HeadingValue& heading_value(); + /*! + * @brief This function copies the value in member heading_confidence + * @param _heading_confidence New value to be copied in member heading_confidence + */ + eProsima_user_DllExport void heading_confidence( + const etsi_its_cam_msgs::msg::HeadingConfidence& _heading_confidence); + + /*! + * @brief This function moves the value in member heading_confidence + * @param _heading_confidence New value to be moved in member heading_confidence + */ + eProsima_user_DllExport void heading_confidence( + etsi_its_cam_msgs::msg::HeadingConfidence&& _heading_confidence); + + /*! + * @brief This function returns a constant reference to member heading_confidence + * @return Constant reference to member heading_confidence + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::HeadingConfidence& heading_confidence() const; + + /*! + * @brief This function returns a reference to member heading_confidence + * @return Reference to member heading_confidence + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::HeadingConfidence& heading_confidence(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::Heading& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::HeadingValue m_heading_value; + etsi_its_cam_msgs::msg::HeadingConfidence m_heading_confidence; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADING_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidence.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidence.cxx new file mode 100644 index 00000000000..a1a724e300b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidence.cxx @@ -0,0 +1,190 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file HeadingConfidence.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "HeadingConfidence.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + +etsi_its_cam_msgs::msg::HeadingConfidence::HeadingConfidence() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@551de37d + m_value = 0; + +} + +etsi_its_cam_msgs::msg::HeadingConfidence::~HeadingConfidence() +{ +} + +etsi_its_cam_msgs::msg::HeadingConfidence::HeadingConfidence( + const HeadingConfidence& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::HeadingConfidence::HeadingConfidence( + HeadingConfidence&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::HeadingConfidence& etsi_its_cam_msgs::msg::HeadingConfidence::operator =( + const HeadingConfidence& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::HeadingConfidence& etsi_its_cam_msgs::msg::HeadingConfidence::operator =( + HeadingConfidence&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::HeadingConfidence::operator ==( + const HeadingConfidence& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::HeadingConfidence::operator !=( + const HeadingConfidence& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::HeadingConfidence::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::HeadingConfidence::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::HeadingConfidence& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::HeadingConfidence::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::HeadingConfidence::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::HeadingConfidence::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::HeadingConfidence::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::HeadingConfidence::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::HeadingConfidence::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::HeadingConfidence::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::HeadingConfidence::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidence.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidence.h new file mode 100644 index 00000000000..624e986be8d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidence.h @@ -0,0 +1,218 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file HeadingConfidence.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGCONFIDENCE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGCONFIDENCE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(HeadingConfidence_SOURCE) +#define HeadingConfidence_DllAPI __declspec( dllexport ) +#else +#define HeadingConfidence_DllAPI __declspec( dllimport ) +#endif // HeadingConfidence_SOURCE +#else +#define HeadingConfidence_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define HeadingConfidence_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace HeadingConfidence_Constants { + const uint8_t MIN = 1; + const uint8_t MAX = 127; + const uint8_t EQUAL_OR_WITHIN_ZERO_POINT_ONE_DEGREE = 1; + const uint8_t EQUAL_OR_WITHIN_ONE_DEGREE = 10; + const uint8_t OUT_OF_RANGE = 126; + const uint8_t UNAVAILABLE = 127; + } // namespace HeadingConfidence_Constants + /*! + * @brief This class represents the structure HeadingConfidence defined by the user in the IDL file. + * @ingroup HEADINGCONFIDENCE + */ + class HeadingConfidence + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport HeadingConfidence(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~HeadingConfidence(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::HeadingConfidence that will be copied. + */ + eProsima_user_DllExport HeadingConfidence( + const HeadingConfidence& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::HeadingConfidence that will be copied. + */ + eProsima_user_DllExport HeadingConfidence( + HeadingConfidence&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::HeadingConfidence that will be copied. + */ + eProsima_user_DllExport HeadingConfidence& operator =( + const HeadingConfidence& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::HeadingConfidence that will be copied. + */ + eProsima_user_DllExport HeadingConfidence& operator =( + HeadingConfidence&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::HeadingConfidence object to compare. + */ + eProsima_user_DllExport bool operator ==( + const HeadingConfidence& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::HeadingConfidence object to compare. + */ + eProsima_user_DllExport bool operator !=( + const HeadingConfidence& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::HeadingConfidence& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGCONFIDENCE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidencePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidencePubSubTypes.cxx new file mode 100644 index 00000000000..0e4159f952f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidencePubSubTypes.cxx @@ -0,0 +1,185 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file HeadingConfidencePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "HeadingConfidencePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace HeadingConfidence_Constants { + + + + + + + + } //End of namespace HeadingConfidence_Constants + HeadingConfidencePubSubType::HeadingConfidencePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::HeadingConfidence_"); + auto type_size = HeadingConfidence::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = HeadingConfidence::isKeyDefined(); + size_t keyLength = HeadingConfidence::getKeyMaxCdrSerializedSize() > 16 ? + HeadingConfidence::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + HeadingConfidencePubSubType::~HeadingConfidencePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool HeadingConfidencePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + HeadingConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool HeadingConfidencePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + HeadingConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function HeadingConfidencePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* HeadingConfidencePubSubType::createData() + { + return reinterpret_cast(new HeadingConfidence()); + } + + void HeadingConfidencePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool HeadingConfidencePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + HeadingConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + HeadingConfidence::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || HeadingConfidence::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidencePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidencePubSubTypes.h new file mode 100644 index 00000000000..5e3cd54f2db --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidencePubSubTypes.h @@ -0,0 +1,116 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file HeadingConfidencePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGCONFIDENCE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGCONFIDENCE_PUBSUBTYPES_H_ + +#include +#include + +#include "HeadingConfidence.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated HeadingConfidence is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace HeadingConfidence_Constants + { + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type HeadingConfidence defined by the user in the IDL file. + * @ingroup HEADINGCONFIDENCE + */ + class HeadingConfidencePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef HeadingConfidence type; + + eProsima_user_DllExport HeadingConfidencePubSubType(); + + eProsima_user_DllExport virtual ~HeadingConfidencePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) HeadingConfidence(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGCONFIDENCE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingPubSubTypes.cxx new file mode 100644 index 00000000000..d5e1f68613f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file HeadingPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "HeadingPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + HeadingPubSubType::HeadingPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::Heading_"); + auto type_size = Heading::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = Heading::isKeyDefined(); + size_t keyLength = Heading::getKeyMaxCdrSerializedSize() > 16 ? + Heading::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + HeadingPubSubType::~HeadingPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool HeadingPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + Heading* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool HeadingPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + Heading* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function HeadingPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* HeadingPubSubType::createData() + { + return reinterpret_cast(new Heading()); + } + + void HeadingPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool HeadingPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + Heading* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + Heading::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || Heading::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingPubSubTypes.h new file mode 100644 index 00000000000..515f0cfb0a5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file HeadingPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADING_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADING_PUBSUBTYPES_H_ + +#include +#include + +#include "Heading.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated Heading is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type Heading defined by the user in the IDL file. + * @ingroup HEADING + */ + class HeadingPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef Heading type; + + eProsima_user_DllExport HeadingPubSubType(); + + eProsima_user_DllExport virtual ~HeadingPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) Heading(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADING_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValue.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValue.cxx new file mode 100644 index 00000000000..253bf878a58 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValue.cxx @@ -0,0 +1,191 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file HeadingValue.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "HeadingValue.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + + +etsi_its_cam_msgs::msg::HeadingValue::HeadingValue() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@7f9ab969 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::HeadingValue::~HeadingValue() +{ +} + +etsi_its_cam_msgs::msg::HeadingValue::HeadingValue( + const HeadingValue& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::HeadingValue::HeadingValue( + HeadingValue&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::HeadingValue& etsi_its_cam_msgs::msg::HeadingValue::operator =( + const HeadingValue& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::HeadingValue& etsi_its_cam_msgs::msg::HeadingValue::operator =( + HeadingValue&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::HeadingValue::operator ==( + const HeadingValue& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::HeadingValue::operator !=( + const HeadingValue& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::HeadingValue::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::HeadingValue::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::HeadingValue& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::HeadingValue::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::HeadingValue::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::HeadingValue::value( + uint16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint16_t etsi_its_cam_msgs::msg::HeadingValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint16_t& etsi_its_cam_msgs::msg::HeadingValue::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::HeadingValue::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::HeadingValue::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::HeadingValue::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValue.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValue.h new file mode 100644 index 00000000000..62e93e34c6b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValue.h @@ -0,0 +1,219 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file HeadingValue.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGVALUE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGVALUE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(HeadingValue_SOURCE) +#define HeadingValue_DllAPI __declspec( dllexport ) +#else +#define HeadingValue_DllAPI __declspec( dllimport ) +#endif // HeadingValue_SOURCE +#else +#define HeadingValue_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define HeadingValue_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace HeadingValue_Constants { + const uint16_t MIN = 0; + const uint16_t MAX = 3601; + const uint16_t WGS_84_NORTH = 0; + const uint16_t WGS_84_EAST = 900; + const uint16_t WGS_84_SOUTH = 1800; + const uint16_t WGS_84_WEST = 2700; + const uint16_t UNAVAILABLE = 3601; + } // namespace HeadingValue_Constants + /*! + * @brief This class represents the structure HeadingValue defined by the user in the IDL file. + * @ingroup HEADINGVALUE + */ + class HeadingValue + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport HeadingValue(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~HeadingValue(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::HeadingValue that will be copied. + */ + eProsima_user_DllExport HeadingValue( + const HeadingValue& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::HeadingValue that will be copied. + */ + eProsima_user_DllExport HeadingValue( + HeadingValue&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::HeadingValue that will be copied. + */ + eProsima_user_DllExport HeadingValue& operator =( + const HeadingValue& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::HeadingValue that will be copied. + */ + eProsima_user_DllExport HeadingValue& operator =( + HeadingValue&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::HeadingValue object to compare. + */ + eProsima_user_DllExport bool operator ==( + const HeadingValue& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::HeadingValue object to compare. + */ + eProsima_user_DllExport bool operator !=( + const HeadingValue& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint16_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint16_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint16_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::HeadingValue& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint16_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGVALUE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValuePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValuePubSubTypes.cxx new file mode 100644 index 00000000000..0c04139e390 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValuePubSubTypes.cxx @@ -0,0 +1,186 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file HeadingValuePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "HeadingValuePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace HeadingValue_Constants { + + + + + + + + + } //End of namespace HeadingValue_Constants + HeadingValuePubSubType::HeadingValuePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::HeadingValue_"); + auto type_size = HeadingValue::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = HeadingValue::isKeyDefined(); + size_t keyLength = HeadingValue::getKeyMaxCdrSerializedSize() > 16 ? + HeadingValue::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + HeadingValuePubSubType::~HeadingValuePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool HeadingValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + HeadingValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool HeadingValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + HeadingValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function HeadingValuePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* HeadingValuePubSubType::createData() + { + return reinterpret_cast(new HeadingValue()); + } + + void HeadingValuePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool HeadingValuePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + HeadingValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + HeadingValue::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || HeadingValue::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValuePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValuePubSubTypes.h new file mode 100644 index 00000000000..4e494522cdb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValuePubSubTypes.h @@ -0,0 +1,117 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file HeadingValuePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGVALUE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGVALUE_PUBSUBTYPES_H_ + +#include +#include + +#include "HeadingValue.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated HeadingValue is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace HeadingValue_Constants + { + + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type HeadingValue defined by the user in the IDL file. + * @ingroup HEADINGVALUE + */ + class HeadingValuePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef HeadingValue type; + + eProsima_user_DllExport HeadingValuePubSubType(); + + eProsima_user_DllExport virtual ~HeadingValuePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) HeadingValue(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGVALUE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainer.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainer.cxx new file mode 100644 index 00000000000..7b5800c4c25 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainer.cxx @@ -0,0 +1,284 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file HighFrequencyContainer.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "HighFrequencyContainer.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + +etsi_its_cam_msgs::msg::HighFrequencyContainer::HighFrequencyContainer() +{ + // m_choice com.eprosima.idl.parser.typecode.PrimitiveTypeCode@9257031 + m_choice = 0; + // m_basic_vehicle_container_high_frequency com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@75201592 + + // m_rsu_container_high_frequency com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@7726e185 + + +} + +etsi_its_cam_msgs::msg::HighFrequencyContainer::~HighFrequencyContainer() +{ + + +} + +etsi_its_cam_msgs::msg::HighFrequencyContainer::HighFrequencyContainer( + const HighFrequencyContainer& x) +{ + m_choice = x.m_choice; + m_basic_vehicle_container_high_frequency = x.m_basic_vehicle_container_high_frequency; + m_rsu_container_high_frequency = x.m_rsu_container_high_frequency; +} + +etsi_its_cam_msgs::msg::HighFrequencyContainer::HighFrequencyContainer( + HighFrequencyContainer&& x) +{ + m_choice = x.m_choice; + m_basic_vehicle_container_high_frequency = std::move(x.m_basic_vehicle_container_high_frequency); + m_rsu_container_high_frequency = std::move(x.m_rsu_container_high_frequency); +} + +etsi_its_cam_msgs::msg::HighFrequencyContainer& etsi_its_cam_msgs::msg::HighFrequencyContainer::operator =( + const HighFrequencyContainer& x) +{ + + m_choice = x.m_choice; + m_basic_vehicle_container_high_frequency = x.m_basic_vehicle_container_high_frequency; + m_rsu_container_high_frequency = x.m_rsu_container_high_frequency; + + return *this; +} + +etsi_its_cam_msgs::msg::HighFrequencyContainer& etsi_its_cam_msgs::msg::HighFrequencyContainer::operator =( + HighFrequencyContainer&& x) +{ + + m_choice = x.m_choice; + m_basic_vehicle_container_high_frequency = std::move(x.m_basic_vehicle_container_high_frequency); + m_rsu_container_high_frequency = std::move(x.m_rsu_container_high_frequency); + + return *this; +} + +bool etsi_its_cam_msgs::msg::HighFrequencyContainer::operator ==( + const HighFrequencyContainer& x) const +{ + + return (m_choice == x.m_choice && m_basic_vehicle_container_high_frequency == x.m_basic_vehicle_container_high_frequency && m_rsu_container_high_frequency == x.m_rsu_container_high_frequency); +} + +bool etsi_its_cam_msgs::msg::HighFrequencyContainer::operator !=( + const HighFrequencyContainer& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::HighFrequencyContainer::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::RSUContainerHighFrequency::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::HighFrequencyContainer::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::HighFrequencyContainer& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency::getCdrSerializedSize(data.basic_vehicle_container_high_frequency(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::RSUContainerHighFrequency::getCdrSerializedSize(data.rsu_container_high_frequency(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::HighFrequencyContainer::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_choice; + scdr << m_basic_vehicle_container_high_frequency; + scdr << m_rsu_container_high_frequency; + +} + +void etsi_its_cam_msgs::msg::HighFrequencyContainer::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_choice; + dcdr >> m_basic_vehicle_container_high_frequency; + dcdr >> m_rsu_container_high_frequency; +} + +/*! + * @brief This function sets a value in member choice + * @param _choice New value for member choice + */ +void etsi_its_cam_msgs::msg::HighFrequencyContainer::choice( + uint8_t _choice) +{ + m_choice = _choice; +} + +/*! + * @brief This function returns the value of member choice + * @return Value of member choice + */ +uint8_t etsi_its_cam_msgs::msg::HighFrequencyContainer::choice() const +{ + return m_choice; +} + +/*! + * @brief This function returns a reference to member choice + * @return Reference to member choice + */ +uint8_t& etsi_its_cam_msgs::msg::HighFrequencyContainer::choice() +{ + return m_choice; +} + +/*! + * @brief This function copies the value in member basic_vehicle_container_high_frequency + * @param _basic_vehicle_container_high_frequency New value to be copied in member basic_vehicle_container_high_frequency + */ +void etsi_its_cam_msgs::msg::HighFrequencyContainer::basic_vehicle_container_high_frequency( + const etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency& _basic_vehicle_container_high_frequency) +{ + m_basic_vehicle_container_high_frequency = _basic_vehicle_container_high_frequency; +} + +/*! + * @brief This function moves the value in member basic_vehicle_container_high_frequency + * @param _basic_vehicle_container_high_frequency New value to be moved in member basic_vehicle_container_high_frequency + */ +void etsi_its_cam_msgs::msg::HighFrequencyContainer::basic_vehicle_container_high_frequency( + etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency&& _basic_vehicle_container_high_frequency) +{ + m_basic_vehicle_container_high_frequency = std::move(_basic_vehicle_container_high_frequency); +} + +/*! + * @brief This function returns a constant reference to member basic_vehicle_container_high_frequency + * @return Constant reference to member basic_vehicle_container_high_frequency + */ +const etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency& etsi_its_cam_msgs::msg::HighFrequencyContainer::basic_vehicle_container_high_frequency() const +{ + return m_basic_vehicle_container_high_frequency; +} + +/*! + * @brief This function returns a reference to member basic_vehicle_container_high_frequency + * @return Reference to member basic_vehicle_container_high_frequency + */ +etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency& etsi_its_cam_msgs::msg::HighFrequencyContainer::basic_vehicle_container_high_frequency() +{ + return m_basic_vehicle_container_high_frequency; +} +/*! + * @brief This function copies the value in member rsu_container_high_frequency + * @param _rsu_container_high_frequency New value to be copied in member rsu_container_high_frequency + */ +void etsi_its_cam_msgs::msg::HighFrequencyContainer::rsu_container_high_frequency( + const etsi_its_cam_msgs::msg::RSUContainerHighFrequency& _rsu_container_high_frequency) +{ + m_rsu_container_high_frequency = _rsu_container_high_frequency; +} + +/*! + * @brief This function moves the value in member rsu_container_high_frequency + * @param _rsu_container_high_frequency New value to be moved in member rsu_container_high_frequency + */ +void etsi_its_cam_msgs::msg::HighFrequencyContainer::rsu_container_high_frequency( + etsi_its_cam_msgs::msg::RSUContainerHighFrequency&& _rsu_container_high_frequency) +{ + m_rsu_container_high_frequency = std::move(_rsu_container_high_frequency); +} + +/*! + * @brief This function returns a constant reference to member rsu_container_high_frequency + * @return Constant reference to member rsu_container_high_frequency + */ +const etsi_its_cam_msgs::msg::RSUContainerHighFrequency& etsi_its_cam_msgs::msg::HighFrequencyContainer::rsu_container_high_frequency() const +{ + return m_rsu_container_high_frequency; +} + +/*! + * @brief This function returns a reference to member rsu_container_high_frequency + * @return Reference to member rsu_container_high_frequency + */ +etsi_its_cam_msgs::msg::RSUContainerHighFrequency& etsi_its_cam_msgs::msg::HighFrequencyContainer::rsu_container_high_frequency() +{ + return m_rsu_container_high_frequency; +} + +size_t etsi_its_cam_msgs::msg::HighFrequencyContainer::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::HighFrequencyContainer::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::HighFrequencyContainer::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainer.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainer.h new file mode 100644 index 00000000000..34cb0e20473 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainer.h @@ -0,0 +1,268 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file HighFrequencyContainer.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HIGHFREQUENCYCONTAINER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HIGHFREQUENCYCONTAINER_H_ + +#include "RSUContainerHighFrequency.h" +#include "BasicVehicleContainerHighFrequency.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(HighFrequencyContainer_SOURCE) +#define HighFrequencyContainer_DllAPI __declspec( dllexport ) +#else +#define HighFrequencyContainer_DllAPI __declspec( dllimport ) +#endif // HighFrequencyContainer_SOURCE +#else +#define HighFrequencyContainer_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define HighFrequencyContainer_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace HighFrequencyContainer_Constants { + const uint8_t CHOICE_BASIC_VEHICLE_CONTAINER_HIGH_FREQUENCY = 0; + const uint8_t CHOICE_RSU_CONTAINER_HIGH_FREQUENCY = 1; + } // namespace HighFrequencyContainer_Constants + /*! + * @brief This class represents the structure HighFrequencyContainer defined by the user in the IDL file. + * @ingroup HIGHFREQUENCYCONTAINER + */ + class HighFrequencyContainer + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport HighFrequencyContainer(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~HighFrequencyContainer(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::HighFrequencyContainer that will be copied. + */ + eProsima_user_DllExport HighFrequencyContainer( + const HighFrequencyContainer& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::HighFrequencyContainer that will be copied. + */ + eProsima_user_DllExport HighFrequencyContainer( + HighFrequencyContainer&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::HighFrequencyContainer that will be copied. + */ + eProsima_user_DllExport HighFrequencyContainer& operator =( + const HighFrequencyContainer& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::HighFrequencyContainer that will be copied. + */ + eProsima_user_DllExport HighFrequencyContainer& operator =( + HighFrequencyContainer&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::HighFrequencyContainer object to compare. + */ + eProsima_user_DllExport bool operator ==( + const HighFrequencyContainer& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::HighFrequencyContainer object to compare. + */ + eProsima_user_DllExport bool operator !=( + const HighFrequencyContainer& x) const; + + /*! + * @brief This function sets a value in member choice + * @param _choice New value for member choice + */ + eProsima_user_DllExport void choice( + uint8_t _choice); + + /*! + * @brief This function returns the value of member choice + * @return Value of member choice + */ + eProsima_user_DllExport uint8_t choice() const; + + /*! + * @brief This function returns a reference to member choice + * @return Reference to member choice + */ + eProsima_user_DllExport uint8_t& choice(); + + /*! + * @brief This function copies the value in member basic_vehicle_container_high_frequency + * @param _basic_vehicle_container_high_frequency New value to be copied in member basic_vehicle_container_high_frequency + */ + eProsima_user_DllExport void basic_vehicle_container_high_frequency( + const etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency& _basic_vehicle_container_high_frequency); + + /*! + * @brief This function moves the value in member basic_vehicle_container_high_frequency + * @param _basic_vehicle_container_high_frequency New value to be moved in member basic_vehicle_container_high_frequency + */ + eProsima_user_DllExport void basic_vehicle_container_high_frequency( + etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency&& _basic_vehicle_container_high_frequency); + + /*! + * @brief This function returns a constant reference to member basic_vehicle_container_high_frequency + * @return Constant reference to member basic_vehicle_container_high_frequency + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency& basic_vehicle_container_high_frequency() const; + + /*! + * @brief This function returns a reference to member basic_vehicle_container_high_frequency + * @return Reference to member basic_vehicle_container_high_frequency + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency& basic_vehicle_container_high_frequency(); + /*! + * @brief This function copies the value in member rsu_container_high_frequency + * @param _rsu_container_high_frequency New value to be copied in member rsu_container_high_frequency + */ + eProsima_user_DllExport void rsu_container_high_frequency( + const etsi_its_cam_msgs::msg::RSUContainerHighFrequency& _rsu_container_high_frequency); + + /*! + * @brief This function moves the value in member rsu_container_high_frequency + * @param _rsu_container_high_frequency New value to be moved in member rsu_container_high_frequency + */ + eProsima_user_DllExport void rsu_container_high_frequency( + etsi_its_cam_msgs::msg::RSUContainerHighFrequency&& _rsu_container_high_frequency); + + /*! + * @brief This function returns a constant reference to member rsu_container_high_frequency + * @return Constant reference to member rsu_container_high_frequency + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::RSUContainerHighFrequency& rsu_container_high_frequency() const; + + /*! + * @brief This function returns a reference to member rsu_container_high_frequency + * @return Reference to member rsu_container_high_frequency + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::RSUContainerHighFrequency& rsu_container_high_frequency(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::HighFrequencyContainer& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_choice; + etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency m_basic_vehicle_container_high_frequency; + etsi_its_cam_msgs::msg::RSUContainerHighFrequency m_rsu_container_high_frequency; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HIGHFREQUENCYCONTAINER_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainerPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainerPubSubTypes.cxx new file mode 100644 index 00000000000..f65737b3134 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainerPubSubTypes.cxx @@ -0,0 +1,181 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file HighFrequencyContainerPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "HighFrequencyContainerPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace HighFrequencyContainer_Constants { + + + + } //End of namespace HighFrequencyContainer_Constants + HighFrequencyContainerPubSubType::HighFrequencyContainerPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::HighFrequencyContainer_"); + auto type_size = HighFrequencyContainer::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = HighFrequencyContainer::isKeyDefined(); + size_t keyLength = HighFrequencyContainer::getKeyMaxCdrSerializedSize() > 16 ? + HighFrequencyContainer::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + HighFrequencyContainerPubSubType::~HighFrequencyContainerPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool HighFrequencyContainerPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + HighFrequencyContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool HighFrequencyContainerPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + HighFrequencyContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function HighFrequencyContainerPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* HighFrequencyContainerPubSubType::createData() + { + return reinterpret_cast(new HighFrequencyContainer()); + } + + void HighFrequencyContainerPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool HighFrequencyContainerPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + HighFrequencyContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + HighFrequencyContainer::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || HighFrequencyContainer::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainerPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainerPubSubTypes.h new file mode 100644 index 00000000000..14ffe108b2e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainerPubSubTypes.h @@ -0,0 +1,112 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file HighFrequencyContainerPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HIGHFREQUENCYCONTAINER_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HIGHFREQUENCYCONTAINER_PUBSUBTYPES_H_ + +#include +#include + +#include "HighFrequencyContainer.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated HighFrequencyContainer is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace HighFrequencyContainer_Constants + { + + + } + /*! + * @brief This class represents the TopicDataType of the type HighFrequencyContainer defined by the user in the IDL file. + * @ingroup HIGHFREQUENCYCONTAINER + */ + class HighFrequencyContainerPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef HighFrequencyContainer type; + + eProsima_user_DllExport HighFrequencyContainerPubSubType(); + + eProsima_user_DllExport virtual ~HighFrequencyContainerPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HIGHFREQUENCYCONTAINER_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeader.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeader.cxx new file mode 100644 index 00000000000..4bac3bd3096 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeader.cxx @@ -0,0 +1,294 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ItsPduHeader.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "ItsPduHeader.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + + + + + + + + + + + + +etsi_its_cam_msgs::msg::ItsPduHeader::ItsPduHeader() +{ + // m_protocol_version com.eprosima.idl.parser.typecode.PrimitiveTypeCode@640f11a1 + m_protocol_version = 0; + // m_message_id com.eprosima.idl.parser.typecode.PrimitiveTypeCode@5c10f1c3 + m_message_id = 0; + // m_station_id com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@7ac2e39b + + +} + +etsi_its_cam_msgs::msg::ItsPduHeader::~ItsPduHeader() +{ + + +} + +etsi_its_cam_msgs::msg::ItsPduHeader::ItsPduHeader( + const ItsPduHeader& x) +{ + m_protocol_version = x.m_protocol_version; + m_message_id = x.m_message_id; + m_station_id = x.m_station_id; +} + +etsi_its_cam_msgs::msg::ItsPduHeader::ItsPduHeader( + ItsPduHeader&& x) +{ + m_protocol_version = x.m_protocol_version; + m_message_id = x.m_message_id; + m_station_id = std::move(x.m_station_id); +} + +etsi_its_cam_msgs::msg::ItsPduHeader& etsi_its_cam_msgs::msg::ItsPduHeader::operator =( + const ItsPduHeader& x) +{ + + m_protocol_version = x.m_protocol_version; + m_message_id = x.m_message_id; + m_station_id = x.m_station_id; + + return *this; +} + +etsi_its_cam_msgs::msg::ItsPduHeader& etsi_its_cam_msgs::msg::ItsPduHeader::operator =( + ItsPduHeader&& x) +{ + + m_protocol_version = x.m_protocol_version; + m_message_id = x.m_message_id; + m_station_id = std::move(x.m_station_id); + + return *this; +} + +bool etsi_its_cam_msgs::msg::ItsPduHeader::operator ==( + const ItsPduHeader& x) const +{ + + return (m_protocol_version == x.m_protocol_version && m_message_id == x.m_message_id && m_station_id == x.m_station_id); +} + +bool etsi_its_cam_msgs::msg::ItsPduHeader::operator !=( + const ItsPduHeader& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::ItsPduHeader::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::StationID::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::ItsPduHeader::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::ItsPduHeader& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::StationID::getCdrSerializedSize(data.station_id(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::ItsPduHeader::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_protocol_version; + scdr << m_message_id; + scdr << m_station_id; + +} + +void etsi_its_cam_msgs::msg::ItsPduHeader::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_protocol_version; + dcdr >> m_message_id; + dcdr >> m_station_id; +} + +/*! + * @brief This function sets a value in member protocol_version + * @param _protocol_version New value for member protocol_version + */ +void etsi_its_cam_msgs::msg::ItsPduHeader::protocol_version( + uint8_t _protocol_version) +{ + m_protocol_version = _protocol_version; +} + +/*! + * @brief This function returns the value of member protocol_version + * @return Value of member protocol_version + */ +uint8_t etsi_its_cam_msgs::msg::ItsPduHeader::protocol_version() const +{ + return m_protocol_version; +} + +/*! + * @brief This function returns a reference to member protocol_version + * @return Reference to member protocol_version + */ +uint8_t& etsi_its_cam_msgs::msg::ItsPduHeader::protocol_version() +{ + return m_protocol_version; +} + +/*! + * @brief This function sets a value in member message_id + * @param _message_id New value for member message_id + */ +void etsi_its_cam_msgs::msg::ItsPduHeader::message_id( + uint8_t _message_id) +{ + m_message_id = _message_id; +} + +/*! + * @brief This function returns the value of member message_id + * @return Value of member message_id + */ +uint8_t etsi_its_cam_msgs::msg::ItsPduHeader::message_id() const +{ + return m_message_id; +} + +/*! + * @brief This function returns a reference to member message_id + * @return Reference to member message_id + */ +uint8_t& etsi_its_cam_msgs::msg::ItsPduHeader::message_id() +{ + return m_message_id; +} + +/*! + * @brief This function copies the value in member station_id + * @param _station_id New value to be copied in member station_id + */ +void etsi_its_cam_msgs::msg::ItsPduHeader::station_id( + const etsi_its_cam_msgs::msg::StationID& _station_id) +{ + m_station_id = _station_id; +} + +/*! + * @brief This function moves the value in member station_id + * @param _station_id New value to be moved in member station_id + */ +void etsi_its_cam_msgs::msg::ItsPduHeader::station_id( + etsi_its_cam_msgs::msg::StationID&& _station_id) +{ + m_station_id = std::move(_station_id); +} + +/*! + * @brief This function returns a constant reference to member station_id + * @return Constant reference to member station_id + */ +const etsi_its_cam_msgs::msg::StationID& etsi_its_cam_msgs::msg::ItsPduHeader::station_id() const +{ + return m_station_id; +} + +/*! + * @brief This function returns a reference to member station_id + * @return Reference to member station_id + */ +etsi_its_cam_msgs::msg::StationID& etsi_its_cam_msgs::msg::ItsPduHeader::station_id() +{ + return m_station_id; +} + +size_t etsi_its_cam_msgs::msg::ItsPduHeader::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::ItsPduHeader::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::ItsPduHeader::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeader.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeader.h new file mode 100644 index 00000000000..916953056a0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeader.h @@ -0,0 +1,276 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ItsPduHeader.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ITSPDUHEADER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ITSPDUHEADER_H_ + +#include "StationID.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(ItsPduHeader_SOURCE) +#define ItsPduHeader_DllAPI __declspec( dllexport ) +#else +#define ItsPduHeader_DllAPI __declspec( dllimport ) +#endif // ItsPduHeader_SOURCE +#else +#define ItsPduHeader_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define ItsPduHeader_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace ItsPduHeader_Constants { + const uint8_t PROTOCOL_VERSION_MIN = 0; + const uint8_t PROTOCOL_VERSION_MAX = 255; + const uint8_t MESSAGE_ID_MIN = 0; + const uint8_t MESSAGE_ID_MAX = 255; + const uint8_t MESSAGE_ID_DENM = 1; + const uint8_t MESSAGE_ID_CAM = 2; + const uint8_t MESSAGE_ID_POI = 3; + const uint8_t MESSAGE_ID_SPATEM = 4; + const uint8_t MESSAGE_ID_MAPEM = 5; + const uint8_t MESSAGE_ID_IVIM = 6; + const uint8_t MESSAGE_ID_EV_RSR = 7; + const uint8_t MESSAGE_ID_TISTPGTRANSACTION = 8; + const uint8_t MESSAGE_ID_SREM = 9; + const uint8_t MESSAGE_ID_SSEM = 10; + const uint8_t MESSAGE_ID_EVCSN = 11; + const uint8_t MESSAGE_ID_SAEM = 12; + const uint8_t MESSAGE_ID_RTCMEM = 13; + } // namespace ItsPduHeader_Constants + /*! + * @brief This class represents the structure ItsPduHeader defined by the user in the IDL file. + * @ingroup ITSPDUHEADER + */ + class ItsPduHeader + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport ItsPduHeader(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~ItsPduHeader(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::ItsPduHeader that will be copied. + */ + eProsima_user_DllExport ItsPduHeader( + const ItsPduHeader& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::ItsPduHeader that will be copied. + */ + eProsima_user_DllExport ItsPduHeader( + ItsPduHeader&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::ItsPduHeader that will be copied. + */ + eProsima_user_DllExport ItsPduHeader& operator =( + const ItsPduHeader& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::ItsPduHeader that will be copied. + */ + eProsima_user_DllExport ItsPduHeader& operator =( + ItsPduHeader&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::ItsPduHeader object to compare. + */ + eProsima_user_DllExport bool operator ==( + const ItsPduHeader& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::ItsPduHeader object to compare. + */ + eProsima_user_DllExport bool operator !=( + const ItsPduHeader& x) const; + + /*! + * @brief This function sets a value in member protocol_version + * @param _protocol_version New value for member protocol_version + */ + eProsima_user_DllExport void protocol_version( + uint8_t _protocol_version); + + /*! + * @brief This function returns the value of member protocol_version + * @return Value of member protocol_version + */ + eProsima_user_DllExport uint8_t protocol_version() const; + + /*! + * @brief This function returns a reference to member protocol_version + * @return Reference to member protocol_version + */ + eProsima_user_DllExport uint8_t& protocol_version(); + + /*! + * @brief This function sets a value in member message_id + * @param _message_id New value for member message_id + */ + eProsima_user_DllExport void message_id( + uint8_t _message_id); + + /*! + * @brief This function returns the value of member message_id + * @return Value of member message_id + */ + eProsima_user_DllExport uint8_t message_id() const; + + /*! + * @brief This function returns a reference to member message_id + * @return Reference to member message_id + */ + eProsima_user_DllExport uint8_t& message_id(); + + /*! + * @brief This function copies the value in member station_id + * @param _station_id New value to be copied in member station_id + */ + eProsima_user_DllExport void station_id( + const etsi_its_cam_msgs::msg::StationID& _station_id); + + /*! + * @brief This function moves the value in member station_id + * @param _station_id New value to be moved in member station_id + */ + eProsima_user_DllExport void station_id( + etsi_its_cam_msgs::msg::StationID&& _station_id); + + /*! + * @brief This function returns a constant reference to member station_id + * @return Constant reference to member station_id + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::StationID& station_id() const; + + /*! + * @brief This function returns a reference to member station_id + * @return Reference to member station_id + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::StationID& station_id(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::ItsPduHeader& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_protocol_version; + uint8_t m_message_id; + etsi_its_cam_msgs::msg::StationID m_station_id; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ITSPDUHEADER_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeaderPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeaderPubSubTypes.cxx new file mode 100644 index 00000000000..2bf6b9d99e2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeaderPubSubTypes.cxx @@ -0,0 +1,196 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ItsPduHeaderPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "ItsPduHeaderPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace ItsPduHeader_Constants { + + + + + + + + + + + + + + + + + + + } //End of namespace ItsPduHeader_Constants + ItsPduHeaderPubSubType::ItsPduHeaderPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::ItsPduHeader_"); + auto type_size = ItsPduHeader::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = ItsPduHeader::isKeyDefined(); + size_t keyLength = ItsPduHeader::getKeyMaxCdrSerializedSize() > 16 ? + ItsPduHeader::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + ItsPduHeaderPubSubType::~ItsPduHeaderPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool ItsPduHeaderPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + ItsPduHeader* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool ItsPduHeaderPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + ItsPduHeader* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function ItsPduHeaderPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* ItsPduHeaderPubSubType::createData() + { + return reinterpret_cast(new ItsPduHeader()); + } + + void ItsPduHeaderPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool ItsPduHeaderPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + ItsPduHeader* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + ItsPduHeader::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || ItsPduHeader::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeaderPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeaderPubSubTypes.h new file mode 100644 index 00000000000..1abb674c166 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeaderPubSubTypes.h @@ -0,0 +1,127 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ItsPduHeaderPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ITSPDUHEADER_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ITSPDUHEADER_PUBSUBTYPES_H_ + +#include +#include + +#include "ItsPduHeader.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated ItsPduHeader is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace ItsPduHeader_Constants + { + + + + + + + + + + + + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type ItsPduHeader defined by the user in the IDL file. + * @ingroup ITSPDUHEADER + */ + class ItsPduHeaderPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef ItsPduHeader type; + + eProsima_user_DllExport ItsPduHeaderPubSubType(); + + eProsima_user_DllExport virtual ~ItsPduHeaderPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) ItsPduHeader(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ITSPDUHEADER_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePosition.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePosition.cxx new file mode 100644 index 00000000000..058af42fbea --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePosition.cxx @@ -0,0 +1,190 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LanePosition.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "LanePosition.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + +etsi_its_cam_msgs::msg::LanePosition::LanePosition() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@1440c311 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::LanePosition::~LanePosition() +{ +} + +etsi_its_cam_msgs::msg::LanePosition::LanePosition( + const LanePosition& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::LanePosition::LanePosition( + LanePosition&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::LanePosition& etsi_its_cam_msgs::msg::LanePosition::operator =( + const LanePosition& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::LanePosition& etsi_its_cam_msgs::msg::LanePosition::operator =( + LanePosition&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::LanePosition::operator ==( + const LanePosition& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::LanePosition::operator !=( + const LanePosition& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::LanePosition::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::LanePosition::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::LanePosition& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::LanePosition::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::LanePosition::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::LanePosition::value( + int8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int8_t etsi_its_cam_msgs::msg::LanePosition::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int8_t& etsi_its_cam_msgs::msg::LanePosition::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::LanePosition::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::LanePosition::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::LanePosition::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePosition.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePosition.h new file mode 100644 index 00000000000..63f760c4b9c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePosition.h @@ -0,0 +1,218 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LanePosition.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LANEPOSITION_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LANEPOSITION_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(LanePosition_SOURCE) +#define LanePosition_DllAPI __declspec( dllexport ) +#else +#define LanePosition_DllAPI __declspec( dllimport ) +#endif // LanePosition_SOURCE +#else +#define LanePosition_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define LanePosition_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace LanePosition_Constants { + const int8_t MIN = -1; + const int8_t MAX = 14; + const int8_t OFF_THE_ROAD = -1; + const int8_t HARD_SHOULDER = 0; + const int8_t OUTERMOST_DRIVING_LANE = 1; + const int8_t SECOND_LANE_FROM_OUTSIDE = 2; + } // namespace LanePosition_Constants + /*! + * @brief This class represents the structure LanePosition defined by the user in the IDL file. + * @ingroup LANEPOSITION + */ + class LanePosition + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport LanePosition(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~LanePosition(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::LanePosition that will be copied. + */ + eProsima_user_DllExport LanePosition( + const LanePosition& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::LanePosition that will be copied. + */ + eProsima_user_DllExport LanePosition( + LanePosition&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::LanePosition that will be copied. + */ + eProsima_user_DllExport LanePosition& operator =( + const LanePosition& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::LanePosition that will be copied. + */ + eProsima_user_DllExport LanePosition& operator =( + LanePosition&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::LanePosition object to compare. + */ + eProsima_user_DllExport bool operator ==( + const LanePosition& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::LanePosition object to compare. + */ + eProsima_user_DllExport bool operator !=( + const LanePosition& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + int8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport int8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport int8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::LanePosition& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + int8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LANEPOSITION_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePositionPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePositionPubSubTypes.cxx new file mode 100644 index 00000000000..8035b88c692 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePositionPubSubTypes.cxx @@ -0,0 +1,185 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LanePositionPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "LanePositionPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace LanePosition_Constants { + + + + + + + + } //End of namespace LanePosition_Constants + LanePositionPubSubType::LanePositionPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::LanePosition_"); + auto type_size = LanePosition::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = LanePosition::isKeyDefined(); + size_t keyLength = LanePosition::getKeyMaxCdrSerializedSize() > 16 ? + LanePosition::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + LanePositionPubSubType::~LanePositionPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool LanePositionPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + LanePosition* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool LanePositionPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + LanePosition* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function LanePositionPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* LanePositionPubSubType::createData() + { + return reinterpret_cast(new LanePosition()); + } + + void LanePositionPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool LanePositionPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + LanePosition* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + LanePosition::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || LanePosition::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePositionPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePositionPubSubTypes.h new file mode 100644 index 00000000000..f08a575bb81 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePositionPubSubTypes.h @@ -0,0 +1,116 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LanePositionPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LANEPOSITION_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LANEPOSITION_PUBSUBTYPES_H_ + +#include +#include + +#include "LanePosition.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated LanePosition is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace LanePosition_Constants + { + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type LanePosition defined by the user in the IDL file. + * @ingroup LANEPOSITION + */ + class LanePositionPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef LanePosition type; + + eProsima_user_DllExport LanePositionPubSubType(); + + eProsima_user_DllExport virtual ~LanePositionPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) LanePosition(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LANEPOSITION_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAcceleration.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAcceleration.cxx new file mode 100644 index 00000000000..62cec7706db --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAcceleration.cxx @@ -0,0 +1,238 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LateralAcceleration.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "LateralAcceleration.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::LateralAcceleration::LateralAcceleration() +{ + // m_lateral_acceleration_value com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@4b1c0397 + + // m_lateral_acceleration_confidence com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@72805168 + + +} + +etsi_its_cam_msgs::msg::LateralAcceleration::~LateralAcceleration() +{ + +} + +etsi_its_cam_msgs::msg::LateralAcceleration::LateralAcceleration( + const LateralAcceleration& x) +{ + m_lateral_acceleration_value = x.m_lateral_acceleration_value; + m_lateral_acceleration_confidence = x.m_lateral_acceleration_confidence; +} + +etsi_its_cam_msgs::msg::LateralAcceleration::LateralAcceleration( + LateralAcceleration&& x) +{ + m_lateral_acceleration_value = std::move(x.m_lateral_acceleration_value); + m_lateral_acceleration_confidence = std::move(x.m_lateral_acceleration_confidence); +} + +etsi_its_cam_msgs::msg::LateralAcceleration& etsi_its_cam_msgs::msg::LateralAcceleration::operator =( + const LateralAcceleration& x) +{ + + m_lateral_acceleration_value = x.m_lateral_acceleration_value; + m_lateral_acceleration_confidence = x.m_lateral_acceleration_confidence; + + return *this; +} + +etsi_its_cam_msgs::msg::LateralAcceleration& etsi_its_cam_msgs::msg::LateralAcceleration::operator =( + LateralAcceleration&& x) +{ + + m_lateral_acceleration_value = std::move(x.m_lateral_acceleration_value); + m_lateral_acceleration_confidence = std::move(x.m_lateral_acceleration_confidence); + + return *this; +} + +bool etsi_its_cam_msgs::msg::LateralAcceleration::operator ==( + const LateralAcceleration& x) const +{ + + return (m_lateral_acceleration_value == x.m_lateral_acceleration_value && m_lateral_acceleration_confidence == x.m_lateral_acceleration_confidence); +} + +bool etsi_its_cam_msgs::msg::LateralAcceleration::operator !=( + const LateralAcceleration& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::LateralAcceleration::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::LateralAccelerationValue::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::AccelerationConfidence::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::LateralAcceleration::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::LateralAcceleration& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::LateralAccelerationValue::getCdrSerializedSize(data.lateral_acceleration_value(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::AccelerationConfidence::getCdrSerializedSize(data.lateral_acceleration_confidence(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::LateralAcceleration::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_lateral_acceleration_value; + scdr << m_lateral_acceleration_confidence; + +} + +void etsi_its_cam_msgs::msg::LateralAcceleration::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_lateral_acceleration_value; + dcdr >> m_lateral_acceleration_confidence; +} + +/*! + * @brief This function copies the value in member lateral_acceleration_value + * @param _lateral_acceleration_value New value to be copied in member lateral_acceleration_value + */ +void etsi_its_cam_msgs::msg::LateralAcceleration::lateral_acceleration_value( + const etsi_its_cam_msgs::msg::LateralAccelerationValue& _lateral_acceleration_value) +{ + m_lateral_acceleration_value = _lateral_acceleration_value; +} + +/*! + * @brief This function moves the value in member lateral_acceleration_value + * @param _lateral_acceleration_value New value to be moved in member lateral_acceleration_value + */ +void etsi_its_cam_msgs::msg::LateralAcceleration::lateral_acceleration_value( + etsi_its_cam_msgs::msg::LateralAccelerationValue&& _lateral_acceleration_value) +{ + m_lateral_acceleration_value = std::move(_lateral_acceleration_value); +} + +/*! + * @brief This function returns a constant reference to member lateral_acceleration_value + * @return Constant reference to member lateral_acceleration_value + */ +const etsi_its_cam_msgs::msg::LateralAccelerationValue& etsi_its_cam_msgs::msg::LateralAcceleration::lateral_acceleration_value() const +{ + return m_lateral_acceleration_value; +} + +/*! + * @brief This function returns a reference to member lateral_acceleration_value + * @return Reference to member lateral_acceleration_value + */ +etsi_its_cam_msgs::msg::LateralAccelerationValue& etsi_its_cam_msgs::msg::LateralAcceleration::lateral_acceleration_value() +{ + return m_lateral_acceleration_value; +} +/*! + * @brief This function copies the value in member lateral_acceleration_confidence + * @param _lateral_acceleration_confidence New value to be copied in member lateral_acceleration_confidence + */ +void etsi_its_cam_msgs::msg::LateralAcceleration::lateral_acceleration_confidence( + const etsi_its_cam_msgs::msg::AccelerationConfidence& _lateral_acceleration_confidence) +{ + m_lateral_acceleration_confidence = _lateral_acceleration_confidence; +} + +/*! + * @brief This function moves the value in member lateral_acceleration_confidence + * @param _lateral_acceleration_confidence New value to be moved in member lateral_acceleration_confidence + */ +void etsi_its_cam_msgs::msg::LateralAcceleration::lateral_acceleration_confidence( + etsi_its_cam_msgs::msg::AccelerationConfidence&& _lateral_acceleration_confidence) +{ + m_lateral_acceleration_confidence = std::move(_lateral_acceleration_confidence); +} + +/*! + * @brief This function returns a constant reference to member lateral_acceleration_confidence + * @return Constant reference to member lateral_acceleration_confidence + */ +const etsi_its_cam_msgs::msg::AccelerationConfidence& etsi_its_cam_msgs::msg::LateralAcceleration::lateral_acceleration_confidence() const +{ + return m_lateral_acceleration_confidence; +} + +/*! + * @brief This function returns a reference to member lateral_acceleration_confidence + * @return Reference to member lateral_acceleration_confidence + */ +etsi_its_cam_msgs::msg::AccelerationConfidence& etsi_its_cam_msgs::msg::LateralAcceleration::lateral_acceleration_confidence() +{ + return m_lateral_acceleration_confidence; +} + +size_t etsi_its_cam_msgs::msg::LateralAcceleration::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::LateralAcceleration::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::LateralAcceleration::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAcceleration.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAcceleration.h new file mode 100644 index 00000000000..aec47b7dca9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAcceleration.h @@ -0,0 +1,244 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LateralAcceleration.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATION_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATION_H_ + +#include "AccelerationConfidence.h" +#include "LateralAccelerationValue.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(LateralAcceleration_SOURCE) +#define LateralAcceleration_DllAPI __declspec( dllexport ) +#else +#define LateralAcceleration_DllAPI __declspec( dllimport ) +#endif // LateralAcceleration_SOURCE +#else +#define LateralAcceleration_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define LateralAcceleration_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure LateralAcceleration defined by the user in the IDL file. + * @ingroup LATERALACCELERATION + */ + class LateralAcceleration + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport LateralAcceleration(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~LateralAcceleration(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::LateralAcceleration that will be copied. + */ + eProsima_user_DllExport LateralAcceleration( + const LateralAcceleration& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::LateralAcceleration that will be copied. + */ + eProsima_user_DllExport LateralAcceleration( + LateralAcceleration&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::LateralAcceleration that will be copied. + */ + eProsima_user_DllExport LateralAcceleration& operator =( + const LateralAcceleration& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::LateralAcceleration that will be copied. + */ + eProsima_user_DllExport LateralAcceleration& operator =( + LateralAcceleration&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::LateralAcceleration object to compare. + */ + eProsima_user_DllExport bool operator ==( + const LateralAcceleration& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::LateralAcceleration object to compare. + */ + eProsima_user_DllExport bool operator !=( + const LateralAcceleration& x) const; + + /*! + * @brief This function copies the value in member lateral_acceleration_value + * @param _lateral_acceleration_value New value to be copied in member lateral_acceleration_value + */ + eProsima_user_DllExport void lateral_acceleration_value( + const etsi_its_cam_msgs::msg::LateralAccelerationValue& _lateral_acceleration_value); + + /*! + * @brief This function moves the value in member lateral_acceleration_value + * @param _lateral_acceleration_value New value to be moved in member lateral_acceleration_value + */ + eProsima_user_DllExport void lateral_acceleration_value( + etsi_its_cam_msgs::msg::LateralAccelerationValue&& _lateral_acceleration_value); + + /*! + * @brief This function returns a constant reference to member lateral_acceleration_value + * @return Constant reference to member lateral_acceleration_value + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::LateralAccelerationValue& lateral_acceleration_value() const; + + /*! + * @brief This function returns a reference to member lateral_acceleration_value + * @return Reference to member lateral_acceleration_value + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::LateralAccelerationValue& lateral_acceleration_value(); + /*! + * @brief This function copies the value in member lateral_acceleration_confidence + * @param _lateral_acceleration_confidence New value to be copied in member lateral_acceleration_confidence + */ + eProsima_user_DllExport void lateral_acceleration_confidence( + const etsi_its_cam_msgs::msg::AccelerationConfidence& _lateral_acceleration_confidence); + + /*! + * @brief This function moves the value in member lateral_acceleration_confidence + * @param _lateral_acceleration_confidence New value to be moved in member lateral_acceleration_confidence + */ + eProsima_user_DllExport void lateral_acceleration_confidence( + etsi_its_cam_msgs::msg::AccelerationConfidence&& _lateral_acceleration_confidence); + + /*! + * @brief This function returns a constant reference to member lateral_acceleration_confidence + * @return Constant reference to member lateral_acceleration_confidence + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::AccelerationConfidence& lateral_acceleration_confidence() const; + + /*! + * @brief This function returns a reference to member lateral_acceleration_confidence + * @return Reference to member lateral_acceleration_confidence + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::AccelerationConfidence& lateral_acceleration_confidence(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::LateralAcceleration& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::LateralAccelerationValue m_lateral_acceleration_value; + etsi_its_cam_msgs::msg::AccelerationConfidence m_lateral_acceleration_confidence; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATION_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationPubSubTypes.cxx new file mode 100644 index 00000000000..0ac8f730b32 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LateralAccelerationPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "LateralAccelerationPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + LateralAccelerationPubSubType::LateralAccelerationPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::LateralAcceleration_"); + auto type_size = LateralAcceleration::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = LateralAcceleration::isKeyDefined(); + size_t keyLength = LateralAcceleration::getKeyMaxCdrSerializedSize() > 16 ? + LateralAcceleration::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + LateralAccelerationPubSubType::~LateralAccelerationPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool LateralAccelerationPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + LateralAcceleration* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool LateralAccelerationPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + LateralAcceleration* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function LateralAccelerationPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* LateralAccelerationPubSubType::createData() + { + return reinterpret_cast(new LateralAcceleration()); + } + + void LateralAccelerationPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool LateralAccelerationPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + LateralAcceleration* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + LateralAcceleration::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || LateralAcceleration::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationPubSubTypes.h new file mode 100644 index 00000000000..4a1deffbe69 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LateralAccelerationPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATION_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATION_PUBSUBTYPES_H_ + +#include +#include + +#include "LateralAcceleration.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated LateralAcceleration is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type LateralAcceleration defined by the user in the IDL file. + * @ingroup LATERALACCELERATION + */ + class LateralAccelerationPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef LateralAcceleration type; + + eProsima_user_DllExport LateralAccelerationPubSubType(); + + eProsima_user_DllExport virtual ~LateralAccelerationPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) LateralAcceleration(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATION_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValue.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValue.cxx new file mode 100644 index 00000000000..7ef9d155c81 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValue.cxx @@ -0,0 +1,189 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LateralAccelerationValue.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "LateralAccelerationValue.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + +etsi_its_cam_msgs::msg::LateralAccelerationValue::LateralAccelerationValue() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@69cac930 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::LateralAccelerationValue::~LateralAccelerationValue() +{ +} + +etsi_its_cam_msgs::msg::LateralAccelerationValue::LateralAccelerationValue( + const LateralAccelerationValue& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::LateralAccelerationValue::LateralAccelerationValue( + LateralAccelerationValue&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::LateralAccelerationValue& etsi_its_cam_msgs::msg::LateralAccelerationValue::operator =( + const LateralAccelerationValue& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::LateralAccelerationValue& etsi_its_cam_msgs::msg::LateralAccelerationValue::operator =( + LateralAccelerationValue&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::LateralAccelerationValue::operator ==( + const LateralAccelerationValue& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::LateralAccelerationValue::operator !=( + const LateralAccelerationValue& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::LateralAccelerationValue::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::LateralAccelerationValue::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::LateralAccelerationValue& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::LateralAccelerationValue::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::LateralAccelerationValue::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::LateralAccelerationValue::value( + int16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int16_t etsi_its_cam_msgs::msg::LateralAccelerationValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int16_t& etsi_its_cam_msgs::msg::LateralAccelerationValue::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::LateralAccelerationValue::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::LateralAccelerationValue::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::LateralAccelerationValue::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValue.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValue.h new file mode 100644 index 00000000000..c4e80103315 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValue.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LateralAccelerationValue.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATIONVALUE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATIONVALUE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(LateralAccelerationValue_SOURCE) +#define LateralAccelerationValue_DllAPI __declspec( dllexport ) +#else +#define LateralAccelerationValue_DllAPI __declspec( dllimport ) +#endif // LateralAccelerationValue_SOURCE +#else +#define LateralAccelerationValue_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define LateralAccelerationValue_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace LateralAccelerationValue_Constants { + const int16_t MIN = -160; + const int16_t MAX = 161; + const int16_t POINT_ONE_METER_PER_SEC_SQUARED_TO_RIGHT = -1; + const int16_t POINT_ONE_METER_PER_SEC_SQUARED_TO_LEFT = 1; + const int16_t UNAVAILABLE = 161; + } // namespace LateralAccelerationValue_Constants + /*! + * @brief This class represents the structure LateralAccelerationValue defined by the user in the IDL file. + * @ingroup LATERALACCELERATIONVALUE + */ + class LateralAccelerationValue + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport LateralAccelerationValue(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~LateralAccelerationValue(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::LateralAccelerationValue that will be copied. + */ + eProsima_user_DllExport LateralAccelerationValue( + const LateralAccelerationValue& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::LateralAccelerationValue that will be copied. + */ + eProsima_user_DllExport LateralAccelerationValue( + LateralAccelerationValue&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::LateralAccelerationValue that will be copied. + */ + eProsima_user_DllExport LateralAccelerationValue& operator =( + const LateralAccelerationValue& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::LateralAccelerationValue that will be copied. + */ + eProsima_user_DllExport LateralAccelerationValue& operator =( + LateralAccelerationValue&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::LateralAccelerationValue object to compare. + */ + eProsima_user_DllExport bool operator ==( + const LateralAccelerationValue& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::LateralAccelerationValue object to compare. + */ + eProsima_user_DllExport bool operator !=( + const LateralAccelerationValue& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + int16_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport int16_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport int16_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::LateralAccelerationValue& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + int16_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATIONVALUE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValuePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValuePubSubTypes.cxx new file mode 100644 index 00000000000..27ab18e9283 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValuePubSubTypes.cxx @@ -0,0 +1,184 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LateralAccelerationValuePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "LateralAccelerationValuePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace LateralAccelerationValue_Constants { + + + + + + + } //End of namespace LateralAccelerationValue_Constants + LateralAccelerationValuePubSubType::LateralAccelerationValuePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::LateralAccelerationValue_"); + auto type_size = LateralAccelerationValue::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = LateralAccelerationValue::isKeyDefined(); + size_t keyLength = LateralAccelerationValue::getKeyMaxCdrSerializedSize() > 16 ? + LateralAccelerationValue::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + LateralAccelerationValuePubSubType::~LateralAccelerationValuePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool LateralAccelerationValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + LateralAccelerationValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool LateralAccelerationValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + LateralAccelerationValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function LateralAccelerationValuePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* LateralAccelerationValuePubSubType::createData() + { + return reinterpret_cast(new LateralAccelerationValue()); + } + + void LateralAccelerationValuePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool LateralAccelerationValuePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + LateralAccelerationValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + LateralAccelerationValue::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || LateralAccelerationValue::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValuePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValuePubSubTypes.h new file mode 100644 index 00000000000..45bcf48ad15 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValuePubSubTypes.h @@ -0,0 +1,115 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LateralAccelerationValuePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATIONVALUE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATIONVALUE_PUBSUBTYPES_H_ + +#include +#include + +#include "LateralAccelerationValue.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated LateralAccelerationValue is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace LateralAccelerationValue_Constants + { + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type LateralAccelerationValue defined by the user in the IDL file. + * @ingroup LATERALACCELERATIONVALUE + */ + class LateralAccelerationValuePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef LateralAccelerationValue type; + + eProsima_user_DllExport LateralAccelerationValuePubSubType(); + + eProsima_user_DllExport virtual ~LateralAccelerationValuePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) LateralAccelerationValue(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATIONVALUE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Latitude.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Latitude.cxx new file mode 100644 index 00000000000..e9c27fb6580 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Latitude.cxx @@ -0,0 +1,189 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Latitude.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Latitude.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + +etsi_its_cam_msgs::msg::Latitude::Latitude() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@62e7dffa + m_value = 0; + +} + +etsi_its_cam_msgs::msg::Latitude::~Latitude() +{ +} + +etsi_its_cam_msgs::msg::Latitude::Latitude( + const Latitude& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::Latitude::Latitude( + Latitude&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::Latitude& etsi_its_cam_msgs::msg::Latitude::operator =( + const Latitude& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::Latitude& etsi_its_cam_msgs::msg::Latitude::operator =( + Latitude&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::Latitude::operator ==( + const Latitude& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::Latitude::operator !=( + const Latitude& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::Latitude::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::Latitude::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::Latitude& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::Latitude::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::Latitude::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::Latitude::value( + int32_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int32_t etsi_its_cam_msgs::msg::Latitude::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int32_t& etsi_its_cam_msgs::msg::Latitude::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::Latitude::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::Latitude::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::Latitude::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Latitude.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Latitude.h new file mode 100644 index 00000000000..1fe8307c384 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Latitude.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Latitude.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATITUDE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATITUDE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(Latitude_SOURCE) +#define Latitude_DllAPI __declspec( dllexport ) +#else +#define Latitude_DllAPI __declspec( dllimport ) +#endif // Latitude_SOURCE +#else +#define Latitude_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define Latitude_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace Latitude_Constants { + const int32_t MIN = -900000000; + const int32_t MAX = 900000001; + const int32_t ONE_MICRODEGREE_NORTH = 10; + const int32_t ONE_MICRODEGREE_SOUTH = -10; + const int32_t UNAVAILABLE = 900000001; + } // namespace Latitude_Constants + /*! + * @brief This class represents the structure Latitude defined by the user in the IDL file. + * @ingroup LATITUDE + */ + class Latitude + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Latitude(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Latitude(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::Latitude that will be copied. + */ + eProsima_user_DllExport Latitude( + const Latitude& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::Latitude that will be copied. + */ + eProsima_user_DllExport Latitude( + Latitude&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::Latitude that will be copied. + */ + eProsima_user_DllExport Latitude& operator =( + const Latitude& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::Latitude that will be copied. + */ + eProsima_user_DllExport Latitude& operator =( + Latitude&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::Latitude object to compare. + */ + eProsima_user_DllExport bool operator ==( + const Latitude& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::Latitude object to compare. + */ + eProsima_user_DllExport bool operator !=( + const Latitude& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + int32_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport int32_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport int32_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::Latitude& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + int32_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATITUDE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LatitudePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LatitudePubSubTypes.cxx new file mode 100644 index 00000000000..383f895acc6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LatitudePubSubTypes.cxx @@ -0,0 +1,184 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LatitudePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "LatitudePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace Latitude_Constants { + + + + + + + } //End of namespace Latitude_Constants + LatitudePubSubType::LatitudePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::Latitude_"); + auto type_size = Latitude::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = Latitude::isKeyDefined(); + size_t keyLength = Latitude::getKeyMaxCdrSerializedSize() > 16 ? + Latitude::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + LatitudePubSubType::~LatitudePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool LatitudePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + Latitude* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool LatitudePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + Latitude* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function LatitudePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* LatitudePubSubType::createData() + { + return reinterpret_cast(new Latitude()); + } + + void LatitudePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool LatitudePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + Latitude* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + Latitude::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || Latitude::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LatitudePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LatitudePubSubTypes.h new file mode 100644 index 00000000000..84953f7f9e1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LatitudePubSubTypes.h @@ -0,0 +1,115 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LatitudePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATITUDE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATITUDE_PUBSUBTYPES_H_ + +#include +#include + +#include "Latitude.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated Latitude is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace Latitude_Constants + { + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type Latitude defined by the user in the IDL file. + * @ingroup LATITUDE + */ + class LatitudePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef Latitude type; + + eProsima_user_DllExport LatitudePubSubType(); + + eProsima_user_DllExport virtual ~LatitudePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) Latitude(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATITUDE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUse.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUse.cxx new file mode 100644 index 00000000000..21b5b41362f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUse.cxx @@ -0,0 +1,250 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LightBarSirenInUse.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "LightBarSirenInUse.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + +etsi_its_cam_msgs::msg::LightBarSirenInUse::LightBarSirenInUse() +{ + // m_value com.eprosima.idl.parser.typecode.SequenceTypeCode@58c540cf + + // m_bits_unused com.eprosima.idl.parser.typecode.PrimitiveTypeCode@3d6300e8 + m_bits_unused = 0; + +} + +etsi_its_cam_msgs::msg::LightBarSirenInUse::~LightBarSirenInUse() +{ + +} + +etsi_its_cam_msgs::msg::LightBarSirenInUse::LightBarSirenInUse( + const LightBarSirenInUse& x) +{ + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; +} + +etsi_its_cam_msgs::msg::LightBarSirenInUse::LightBarSirenInUse( + LightBarSirenInUse&& x) +{ + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; +} + +etsi_its_cam_msgs::msg::LightBarSirenInUse& etsi_its_cam_msgs::msg::LightBarSirenInUse::operator =( + const LightBarSirenInUse& x) +{ + + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; + + return *this; +} + +etsi_its_cam_msgs::msg::LightBarSirenInUse& etsi_its_cam_msgs::msg::LightBarSirenInUse::operator =( + LightBarSirenInUse&& x) +{ + + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; + + return *this; +} + +bool etsi_its_cam_msgs::msg::LightBarSirenInUse::operator ==( + const LightBarSirenInUse& x) const +{ + + return (m_value == x.m_value && m_bits_unused == x.m_bits_unused); +} + +bool etsi_its_cam_msgs::msg::LightBarSirenInUse::operator !=( + const LightBarSirenInUse& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::LightBarSirenInUse::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + current_alignment += (100 * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::LightBarSirenInUse::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::LightBarSirenInUse& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + if (data.value().size() > 0) + { + current_alignment += (data.value().size() * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + } + + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::LightBarSirenInUse::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + scdr << m_bits_unused; + +} + +void etsi_its_cam_msgs::msg::LightBarSirenInUse::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; + dcdr >> m_bits_unused; +} + +/*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ +void etsi_its_cam_msgs::msg::LightBarSirenInUse::value( + const std::vector& _value) +{ + m_value = _value; +} + +/*! + * @brief This function moves the value in member value + * @param _value New value to be moved in member value + */ +void etsi_its_cam_msgs::msg::LightBarSirenInUse::value( + std::vector&& _value) +{ + m_value = std::move(_value); +} + +/*! + * @brief This function returns a constant reference to member value + * @return Constant reference to member value + */ +const std::vector& etsi_its_cam_msgs::msg::LightBarSirenInUse::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +std::vector& etsi_its_cam_msgs::msg::LightBarSirenInUse::value() +{ + return m_value; +} +/*! + * @brief This function sets a value in member bits_unused + * @param _bits_unused New value for member bits_unused + */ +void etsi_its_cam_msgs::msg::LightBarSirenInUse::bits_unused( + uint8_t _bits_unused) +{ + m_bits_unused = _bits_unused; +} + +/*! + * @brief This function returns the value of member bits_unused + * @return Value of member bits_unused + */ +uint8_t etsi_its_cam_msgs::msg::LightBarSirenInUse::bits_unused() const +{ + return m_bits_unused; +} + +/*! + * @brief This function returns a reference to member bits_unused + * @return Reference to member bits_unused + */ +uint8_t& etsi_its_cam_msgs::msg::LightBarSirenInUse::bits_unused() +{ + return m_bits_unused; +} + + +size_t etsi_its_cam_msgs::msg::LightBarSirenInUse::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::LightBarSirenInUse::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::LightBarSirenInUse::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUse.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUse.h new file mode 100644 index 00000000000..fe86dd27329 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUse.h @@ -0,0 +1,241 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LightBarSirenInUse.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LIGHTBARSIRENINUSE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LIGHTBARSIRENINUSE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(LightBarSirenInUse_SOURCE) +#define LightBarSirenInUse_DllAPI __declspec( dllexport ) +#else +#define LightBarSirenInUse_DllAPI __declspec( dllimport ) +#endif // LightBarSirenInUse_SOURCE +#else +#define LightBarSirenInUse_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define LightBarSirenInUse_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace LightBarSirenInUse_Constants { + const uint8_t SIZE_BITS = 2; + const uint8_t BIT_INDEX_LIGHT_BAR_ACTIVATED = 0; + const uint8_t BIT_INDEX_SIREN_ACTIVATED = 1; + } // namespace LightBarSirenInUse_Constants + /*! + * @brief This class represents the structure LightBarSirenInUse defined by the user in the IDL file. + * @ingroup LIGHTBARSIRENINUSE + */ + class LightBarSirenInUse + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport LightBarSirenInUse(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~LightBarSirenInUse(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::LightBarSirenInUse that will be copied. + */ + eProsima_user_DllExport LightBarSirenInUse( + const LightBarSirenInUse& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::LightBarSirenInUse that will be copied. + */ + eProsima_user_DllExport LightBarSirenInUse( + LightBarSirenInUse&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::LightBarSirenInUse that will be copied. + */ + eProsima_user_DllExport LightBarSirenInUse& operator =( + const LightBarSirenInUse& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::LightBarSirenInUse that will be copied. + */ + eProsima_user_DllExport LightBarSirenInUse& operator =( + LightBarSirenInUse&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::LightBarSirenInUse object to compare. + */ + eProsima_user_DllExport bool operator ==( + const LightBarSirenInUse& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::LightBarSirenInUse object to compare. + */ + eProsima_user_DllExport bool operator !=( + const LightBarSirenInUse& x) const; + + /*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ + eProsima_user_DllExport void value( + const std::vector& _value); + + /*! + * @brief This function moves the value in member value + * @param _value New value to be moved in member value + */ + eProsima_user_DllExport void value( + std::vector&& _value); + + /*! + * @brief This function returns a constant reference to member value + * @return Constant reference to member value + */ + eProsima_user_DllExport const std::vector& value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport std::vector& value(); + /*! + * @brief This function sets a value in member bits_unused + * @param _bits_unused New value for member bits_unused + */ + eProsima_user_DllExport void bits_unused( + uint8_t _bits_unused); + + /*! + * @brief This function returns the value of member bits_unused + * @return Value of member bits_unused + */ + eProsima_user_DllExport uint8_t bits_unused() const; + + /*! + * @brief This function returns a reference to member bits_unused + * @return Reference to member bits_unused + */ + eProsima_user_DllExport uint8_t& bits_unused(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::LightBarSirenInUse& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std::vector m_value; + uint8_t m_bits_unused; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LIGHTBARSIRENINUSE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUsePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUsePubSubTypes.cxx new file mode 100644 index 00000000000..a634d0d7409 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUsePubSubTypes.cxx @@ -0,0 +1,182 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LightBarSirenInUsePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "LightBarSirenInUsePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace LightBarSirenInUse_Constants { + + + + + } //End of namespace LightBarSirenInUse_Constants + LightBarSirenInUsePubSubType::LightBarSirenInUsePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::LightBarSirenInUse_"); + auto type_size = LightBarSirenInUse::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = LightBarSirenInUse::isKeyDefined(); + size_t keyLength = LightBarSirenInUse::getKeyMaxCdrSerializedSize() > 16 ? + LightBarSirenInUse::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + LightBarSirenInUsePubSubType::~LightBarSirenInUsePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool LightBarSirenInUsePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + LightBarSirenInUse* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool LightBarSirenInUsePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + LightBarSirenInUse* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function LightBarSirenInUsePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* LightBarSirenInUsePubSubType::createData() + { + return reinterpret_cast(new LightBarSirenInUse()); + } + + void LightBarSirenInUsePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool LightBarSirenInUsePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + LightBarSirenInUse* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + LightBarSirenInUse::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || LightBarSirenInUse::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUsePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUsePubSubTypes.h new file mode 100644 index 00000000000..534b5f3043a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUsePubSubTypes.h @@ -0,0 +1,113 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LightBarSirenInUsePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LIGHTBARSIRENINUSE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LIGHTBARSIRENINUSE_PUBSUBTYPES_H_ + +#include +#include + +#include "LightBarSirenInUse.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated LightBarSirenInUse is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace LightBarSirenInUse_Constants + { + + + + } + /*! + * @brief This class represents the TopicDataType of the type LightBarSirenInUse defined by the user in the IDL file. + * @ingroup LIGHTBARSIRENINUSE + */ + class LightBarSirenInUsePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef LightBarSirenInUse type; + + eProsima_user_DllExport LightBarSirenInUsePubSubType(); + + eProsima_user_DllExport virtual ~LightBarSirenInUsePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LIGHTBARSIRENINUSE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Longitude.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Longitude.cxx new file mode 100644 index 00000000000..88d133a50ce --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Longitude.cxx @@ -0,0 +1,189 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Longitude.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Longitude.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + +etsi_its_cam_msgs::msg::Longitude::Longitude() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@4567e53d + m_value = 0; + +} + +etsi_its_cam_msgs::msg::Longitude::~Longitude() +{ +} + +etsi_its_cam_msgs::msg::Longitude::Longitude( + const Longitude& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::Longitude::Longitude( + Longitude&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::Longitude& etsi_its_cam_msgs::msg::Longitude::operator =( + const Longitude& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::Longitude& etsi_its_cam_msgs::msg::Longitude::operator =( + Longitude&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::Longitude::operator ==( + const Longitude& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::Longitude::operator !=( + const Longitude& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::Longitude::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::Longitude::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::Longitude& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::Longitude::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::Longitude::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::Longitude::value( + int32_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int32_t etsi_its_cam_msgs::msg::Longitude::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int32_t& etsi_its_cam_msgs::msg::Longitude::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::Longitude::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::Longitude::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::Longitude::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Longitude.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Longitude.h new file mode 100644 index 00000000000..b80e52005aa --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Longitude.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Longitude.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(Longitude_SOURCE) +#define Longitude_DllAPI __declspec( dllexport ) +#else +#define Longitude_DllAPI __declspec( dllimport ) +#endif // Longitude_SOURCE +#else +#define Longitude_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define Longitude_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace Longitude_Constants { + const int32_t MIN = -1800000000; + const int32_t MAX = 1800000001; + const int32_t ONE_MICRODEGREE_EAST = 10; + const int32_t ONE_MICRODEGREE_WEST = -10; + const int32_t UNAVAILABLE = 1800000001; + } // namespace Longitude_Constants + /*! + * @brief This class represents the structure Longitude defined by the user in the IDL file. + * @ingroup LONGITUDE + */ + class Longitude + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Longitude(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Longitude(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::Longitude that will be copied. + */ + eProsima_user_DllExport Longitude( + const Longitude& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::Longitude that will be copied. + */ + eProsima_user_DllExport Longitude( + Longitude&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::Longitude that will be copied. + */ + eProsima_user_DllExport Longitude& operator =( + const Longitude& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::Longitude that will be copied. + */ + eProsima_user_DllExport Longitude& operator =( + Longitude&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::Longitude object to compare. + */ + eProsima_user_DllExport bool operator ==( + const Longitude& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::Longitude object to compare. + */ + eProsima_user_DllExport bool operator !=( + const Longitude& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + int32_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport int32_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport int32_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::Longitude& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + int32_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudePubSubTypes.cxx new file mode 100644 index 00000000000..6105d93aa80 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudePubSubTypes.cxx @@ -0,0 +1,184 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LongitudePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "LongitudePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace Longitude_Constants { + + + + + + + } //End of namespace Longitude_Constants + LongitudePubSubType::LongitudePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::Longitude_"); + auto type_size = Longitude::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = Longitude::isKeyDefined(); + size_t keyLength = Longitude::getKeyMaxCdrSerializedSize() > 16 ? + Longitude::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + LongitudePubSubType::~LongitudePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool LongitudePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + Longitude* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool LongitudePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + Longitude* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function LongitudePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* LongitudePubSubType::createData() + { + return reinterpret_cast(new Longitude()); + } + + void LongitudePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool LongitudePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + Longitude* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + Longitude::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || Longitude::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudePubSubTypes.h new file mode 100644 index 00000000000..70344c0d10a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudePubSubTypes.h @@ -0,0 +1,115 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LongitudePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDE_PUBSUBTYPES_H_ + +#include +#include + +#include "Longitude.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated Longitude is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace Longitude_Constants + { + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type Longitude defined by the user in the IDL file. + * @ingroup LONGITUDE + */ + class LongitudePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef Longitude type; + + eProsima_user_DllExport LongitudePubSubType(); + + eProsima_user_DllExport virtual ~LongitudePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) Longitude(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAcceleration.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAcceleration.cxx new file mode 100644 index 00000000000..9c5163824c3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAcceleration.cxx @@ -0,0 +1,238 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LongitudinalAcceleration.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "LongitudinalAcceleration.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::LongitudinalAcceleration::LongitudinalAcceleration() +{ + // m_longitudinal_acceleration_value com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@301d8120 + + // m_longitudinal_acceleration_confidence com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@6d367020 + + +} + +etsi_its_cam_msgs::msg::LongitudinalAcceleration::~LongitudinalAcceleration() +{ + +} + +etsi_its_cam_msgs::msg::LongitudinalAcceleration::LongitudinalAcceleration( + const LongitudinalAcceleration& x) +{ + m_longitudinal_acceleration_value = x.m_longitudinal_acceleration_value; + m_longitudinal_acceleration_confidence = x.m_longitudinal_acceleration_confidence; +} + +etsi_its_cam_msgs::msg::LongitudinalAcceleration::LongitudinalAcceleration( + LongitudinalAcceleration&& x) +{ + m_longitudinal_acceleration_value = std::move(x.m_longitudinal_acceleration_value); + m_longitudinal_acceleration_confidence = std::move(x.m_longitudinal_acceleration_confidence); +} + +etsi_its_cam_msgs::msg::LongitudinalAcceleration& etsi_its_cam_msgs::msg::LongitudinalAcceleration::operator =( + const LongitudinalAcceleration& x) +{ + + m_longitudinal_acceleration_value = x.m_longitudinal_acceleration_value; + m_longitudinal_acceleration_confidence = x.m_longitudinal_acceleration_confidence; + + return *this; +} + +etsi_its_cam_msgs::msg::LongitudinalAcceleration& etsi_its_cam_msgs::msg::LongitudinalAcceleration::operator =( + LongitudinalAcceleration&& x) +{ + + m_longitudinal_acceleration_value = std::move(x.m_longitudinal_acceleration_value); + m_longitudinal_acceleration_confidence = std::move(x.m_longitudinal_acceleration_confidence); + + return *this; +} + +bool etsi_its_cam_msgs::msg::LongitudinalAcceleration::operator ==( + const LongitudinalAcceleration& x) const +{ + + return (m_longitudinal_acceleration_value == x.m_longitudinal_acceleration_value && m_longitudinal_acceleration_confidence == x.m_longitudinal_acceleration_confidence); +} + +bool etsi_its_cam_msgs::msg::LongitudinalAcceleration::operator !=( + const LongitudinalAcceleration& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::LongitudinalAcceleration::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::LongitudinalAccelerationValue::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::AccelerationConfidence::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::LongitudinalAcceleration::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::LongitudinalAcceleration& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::LongitudinalAccelerationValue::getCdrSerializedSize(data.longitudinal_acceleration_value(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::AccelerationConfidence::getCdrSerializedSize(data.longitudinal_acceleration_confidence(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::LongitudinalAcceleration::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_longitudinal_acceleration_value; + scdr << m_longitudinal_acceleration_confidence; + +} + +void etsi_its_cam_msgs::msg::LongitudinalAcceleration::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_longitudinal_acceleration_value; + dcdr >> m_longitudinal_acceleration_confidence; +} + +/*! + * @brief This function copies the value in member longitudinal_acceleration_value + * @param _longitudinal_acceleration_value New value to be copied in member longitudinal_acceleration_value + */ +void etsi_its_cam_msgs::msg::LongitudinalAcceleration::longitudinal_acceleration_value( + const etsi_its_cam_msgs::msg::LongitudinalAccelerationValue& _longitudinal_acceleration_value) +{ + m_longitudinal_acceleration_value = _longitudinal_acceleration_value; +} + +/*! + * @brief This function moves the value in member longitudinal_acceleration_value + * @param _longitudinal_acceleration_value New value to be moved in member longitudinal_acceleration_value + */ +void etsi_its_cam_msgs::msg::LongitudinalAcceleration::longitudinal_acceleration_value( + etsi_its_cam_msgs::msg::LongitudinalAccelerationValue&& _longitudinal_acceleration_value) +{ + m_longitudinal_acceleration_value = std::move(_longitudinal_acceleration_value); +} + +/*! + * @brief This function returns a constant reference to member longitudinal_acceleration_value + * @return Constant reference to member longitudinal_acceleration_value + */ +const etsi_its_cam_msgs::msg::LongitudinalAccelerationValue& etsi_its_cam_msgs::msg::LongitudinalAcceleration::longitudinal_acceleration_value() const +{ + return m_longitudinal_acceleration_value; +} + +/*! + * @brief This function returns a reference to member longitudinal_acceleration_value + * @return Reference to member longitudinal_acceleration_value + */ +etsi_its_cam_msgs::msg::LongitudinalAccelerationValue& etsi_its_cam_msgs::msg::LongitudinalAcceleration::longitudinal_acceleration_value() +{ + return m_longitudinal_acceleration_value; +} +/*! + * @brief This function copies the value in member longitudinal_acceleration_confidence + * @param _longitudinal_acceleration_confidence New value to be copied in member longitudinal_acceleration_confidence + */ +void etsi_its_cam_msgs::msg::LongitudinalAcceleration::longitudinal_acceleration_confidence( + const etsi_its_cam_msgs::msg::AccelerationConfidence& _longitudinal_acceleration_confidence) +{ + m_longitudinal_acceleration_confidence = _longitudinal_acceleration_confidence; +} + +/*! + * @brief This function moves the value in member longitudinal_acceleration_confidence + * @param _longitudinal_acceleration_confidence New value to be moved in member longitudinal_acceleration_confidence + */ +void etsi_its_cam_msgs::msg::LongitudinalAcceleration::longitudinal_acceleration_confidence( + etsi_its_cam_msgs::msg::AccelerationConfidence&& _longitudinal_acceleration_confidence) +{ + m_longitudinal_acceleration_confidence = std::move(_longitudinal_acceleration_confidence); +} + +/*! + * @brief This function returns a constant reference to member longitudinal_acceleration_confidence + * @return Constant reference to member longitudinal_acceleration_confidence + */ +const etsi_its_cam_msgs::msg::AccelerationConfidence& etsi_its_cam_msgs::msg::LongitudinalAcceleration::longitudinal_acceleration_confidence() const +{ + return m_longitudinal_acceleration_confidence; +} + +/*! + * @brief This function returns a reference to member longitudinal_acceleration_confidence + * @return Reference to member longitudinal_acceleration_confidence + */ +etsi_its_cam_msgs::msg::AccelerationConfidence& etsi_its_cam_msgs::msg::LongitudinalAcceleration::longitudinal_acceleration_confidence() +{ + return m_longitudinal_acceleration_confidence; +} + +size_t etsi_its_cam_msgs::msg::LongitudinalAcceleration::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::LongitudinalAcceleration::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::LongitudinalAcceleration::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAcceleration.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAcceleration.h new file mode 100644 index 00000000000..589ba9b5039 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAcceleration.h @@ -0,0 +1,244 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LongitudinalAcceleration.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATION_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATION_H_ + +#include "LongitudinalAccelerationValue.h" +#include "AccelerationConfidence.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(LongitudinalAcceleration_SOURCE) +#define LongitudinalAcceleration_DllAPI __declspec( dllexport ) +#else +#define LongitudinalAcceleration_DllAPI __declspec( dllimport ) +#endif // LongitudinalAcceleration_SOURCE +#else +#define LongitudinalAcceleration_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define LongitudinalAcceleration_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure LongitudinalAcceleration defined by the user in the IDL file. + * @ingroup LONGITUDINALACCELERATION + */ + class LongitudinalAcceleration + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport LongitudinalAcceleration(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~LongitudinalAcceleration(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::LongitudinalAcceleration that will be copied. + */ + eProsima_user_DllExport LongitudinalAcceleration( + const LongitudinalAcceleration& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::LongitudinalAcceleration that will be copied. + */ + eProsima_user_DllExport LongitudinalAcceleration( + LongitudinalAcceleration&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::LongitudinalAcceleration that will be copied. + */ + eProsima_user_DllExport LongitudinalAcceleration& operator =( + const LongitudinalAcceleration& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::LongitudinalAcceleration that will be copied. + */ + eProsima_user_DllExport LongitudinalAcceleration& operator =( + LongitudinalAcceleration&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::LongitudinalAcceleration object to compare. + */ + eProsima_user_DllExport bool operator ==( + const LongitudinalAcceleration& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::LongitudinalAcceleration object to compare. + */ + eProsima_user_DllExport bool operator !=( + const LongitudinalAcceleration& x) const; + + /*! + * @brief This function copies the value in member longitudinal_acceleration_value + * @param _longitudinal_acceleration_value New value to be copied in member longitudinal_acceleration_value + */ + eProsima_user_DllExport void longitudinal_acceleration_value( + const etsi_its_cam_msgs::msg::LongitudinalAccelerationValue& _longitudinal_acceleration_value); + + /*! + * @brief This function moves the value in member longitudinal_acceleration_value + * @param _longitudinal_acceleration_value New value to be moved in member longitudinal_acceleration_value + */ + eProsima_user_DllExport void longitudinal_acceleration_value( + etsi_its_cam_msgs::msg::LongitudinalAccelerationValue&& _longitudinal_acceleration_value); + + /*! + * @brief This function returns a constant reference to member longitudinal_acceleration_value + * @return Constant reference to member longitudinal_acceleration_value + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::LongitudinalAccelerationValue& longitudinal_acceleration_value() const; + + /*! + * @brief This function returns a reference to member longitudinal_acceleration_value + * @return Reference to member longitudinal_acceleration_value + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::LongitudinalAccelerationValue& longitudinal_acceleration_value(); + /*! + * @brief This function copies the value in member longitudinal_acceleration_confidence + * @param _longitudinal_acceleration_confidence New value to be copied in member longitudinal_acceleration_confidence + */ + eProsima_user_DllExport void longitudinal_acceleration_confidence( + const etsi_its_cam_msgs::msg::AccelerationConfidence& _longitudinal_acceleration_confidence); + + /*! + * @brief This function moves the value in member longitudinal_acceleration_confidence + * @param _longitudinal_acceleration_confidence New value to be moved in member longitudinal_acceleration_confidence + */ + eProsima_user_DllExport void longitudinal_acceleration_confidence( + etsi_its_cam_msgs::msg::AccelerationConfidence&& _longitudinal_acceleration_confidence); + + /*! + * @brief This function returns a constant reference to member longitudinal_acceleration_confidence + * @return Constant reference to member longitudinal_acceleration_confidence + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::AccelerationConfidence& longitudinal_acceleration_confidence() const; + + /*! + * @brief This function returns a reference to member longitudinal_acceleration_confidence + * @return Reference to member longitudinal_acceleration_confidence + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::AccelerationConfidence& longitudinal_acceleration_confidence(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::LongitudinalAcceleration& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::LongitudinalAccelerationValue m_longitudinal_acceleration_value; + etsi_its_cam_msgs::msg::AccelerationConfidence m_longitudinal_acceleration_confidence; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATION_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationPubSubTypes.cxx new file mode 100644 index 00000000000..1ab3dc03357 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LongitudinalAccelerationPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "LongitudinalAccelerationPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + LongitudinalAccelerationPubSubType::LongitudinalAccelerationPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::LongitudinalAcceleration_"); + auto type_size = LongitudinalAcceleration::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = LongitudinalAcceleration::isKeyDefined(); + size_t keyLength = LongitudinalAcceleration::getKeyMaxCdrSerializedSize() > 16 ? + LongitudinalAcceleration::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + LongitudinalAccelerationPubSubType::~LongitudinalAccelerationPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool LongitudinalAccelerationPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + LongitudinalAcceleration* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool LongitudinalAccelerationPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + LongitudinalAcceleration* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function LongitudinalAccelerationPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* LongitudinalAccelerationPubSubType::createData() + { + return reinterpret_cast(new LongitudinalAcceleration()); + } + + void LongitudinalAccelerationPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool LongitudinalAccelerationPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + LongitudinalAcceleration* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + LongitudinalAcceleration::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || LongitudinalAcceleration::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationPubSubTypes.h new file mode 100644 index 00000000000..78167e51a6b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LongitudinalAccelerationPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATION_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATION_PUBSUBTYPES_H_ + +#include +#include + +#include "LongitudinalAcceleration.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated LongitudinalAcceleration is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type LongitudinalAcceleration defined by the user in the IDL file. + * @ingroup LONGITUDINALACCELERATION + */ + class LongitudinalAccelerationPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef LongitudinalAcceleration type; + + eProsima_user_DllExport LongitudinalAccelerationPubSubType(); + + eProsima_user_DllExport virtual ~LongitudinalAccelerationPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) LongitudinalAcceleration(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATION_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.cxx new file mode 100644 index 00000000000..5225678785d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.cxx @@ -0,0 +1,189 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LongitudinalAccelerationValue.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "LongitudinalAccelerationValue.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + +etsi_its_cam_msgs::msg::LongitudinalAccelerationValue::LongitudinalAccelerationValue() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@5cbb84b1 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::LongitudinalAccelerationValue::~LongitudinalAccelerationValue() +{ +} + +etsi_its_cam_msgs::msg::LongitudinalAccelerationValue::LongitudinalAccelerationValue( + const LongitudinalAccelerationValue& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::LongitudinalAccelerationValue::LongitudinalAccelerationValue( + LongitudinalAccelerationValue&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::LongitudinalAccelerationValue& etsi_its_cam_msgs::msg::LongitudinalAccelerationValue::operator =( + const LongitudinalAccelerationValue& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::LongitudinalAccelerationValue& etsi_its_cam_msgs::msg::LongitudinalAccelerationValue::operator =( + LongitudinalAccelerationValue&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::LongitudinalAccelerationValue::operator ==( + const LongitudinalAccelerationValue& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::LongitudinalAccelerationValue::operator !=( + const LongitudinalAccelerationValue& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::LongitudinalAccelerationValue::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::LongitudinalAccelerationValue::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::LongitudinalAccelerationValue& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::LongitudinalAccelerationValue::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::LongitudinalAccelerationValue::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::LongitudinalAccelerationValue::value( + int16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int16_t etsi_its_cam_msgs::msg::LongitudinalAccelerationValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int16_t& etsi_its_cam_msgs::msg::LongitudinalAccelerationValue::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::LongitudinalAccelerationValue::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::LongitudinalAccelerationValue::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::LongitudinalAccelerationValue::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.h new file mode 100644 index 00000000000..4cd69e3e7fe --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LongitudinalAccelerationValue.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATIONVALUE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATIONVALUE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(LongitudinalAccelerationValue_SOURCE) +#define LongitudinalAccelerationValue_DllAPI __declspec( dllexport ) +#else +#define LongitudinalAccelerationValue_DllAPI __declspec( dllimport ) +#endif // LongitudinalAccelerationValue_SOURCE +#else +#define LongitudinalAccelerationValue_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define LongitudinalAccelerationValue_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace LongitudinalAccelerationValue_Constants { + const int16_t MIN = -160; + const int16_t MAX = 161; + const int16_t POINT_ONE_METER_PER_SEC_SQUARED_FORWARD = 1; + const int16_t POINT_ONE_METER_PER_SEC_SQUARED_BACKWARD = -1; + const int16_t UNAVAILABLE = 161; + } // namespace LongitudinalAccelerationValue_Constants + /*! + * @brief This class represents the structure LongitudinalAccelerationValue defined by the user in the IDL file. + * @ingroup LONGITUDINALACCELERATIONVALUE + */ + class LongitudinalAccelerationValue + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport LongitudinalAccelerationValue(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~LongitudinalAccelerationValue(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::LongitudinalAccelerationValue that will be copied. + */ + eProsima_user_DllExport LongitudinalAccelerationValue( + const LongitudinalAccelerationValue& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::LongitudinalAccelerationValue that will be copied. + */ + eProsima_user_DllExport LongitudinalAccelerationValue( + LongitudinalAccelerationValue&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::LongitudinalAccelerationValue that will be copied. + */ + eProsima_user_DllExport LongitudinalAccelerationValue& operator =( + const LongitudinalAccelerationValue& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::LongitudinalAccelerationValue that will be copied. + */ + eProsima_user_DllExport LongitudinalAccelerationValue& operator =( + LongitudinalAccelerationValue&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::LongitudinalAccelerationValue object to compare. + */ + eProsima_user_DllExport bool operator ==( + const LongitudinalAccelerationValue& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::LongitudinalAccelerationValue object to compare. + */ + eProsima_user_DllExport bool operator !=( + const LongitudinalAccelerationValue& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + int16_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport int16_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport int16_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::LongitudinalAccelerationValue& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + int16_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATIONVALUE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValuePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValuePubSubTypes.cxx new file mode 100644 index 00000000000..cc3643f6b50 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValuePubSubTypes.cxx @@ -0,0 +1,184 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LongitudinalAccelerationValuePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "LongitudinalAccelerationValuePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace LongitudinalAccelerationValue_Constants { + + + + + + + } //End of namespace LongitudinalAccelerationValue_Constants + LongitudinalAccelerationValuePubSubType::LongitudinalAccelerationValuePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::LongitudinalAccelerationValue_"); + auto type_size = LongitudinalAccelerationValue::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = LongitudinalAccelerationValue::isKeyDefined(); + size_t keyLength = LongitudinalAccelerationValue::getKeyMaxCdrSerializedSize() > 16 ? + LongitudinalAccelerationValue::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + LongitudinalAccelerationValuePubSubType::~LongitudinalAccelerationValuePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool LongitudinalAccelerationValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + LongitudinalAccelerationValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool LongitudinalAccelerationValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + LongitudinalAccelerationValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function LongitudinalAccelerationValuePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* LongitudinalAccelerationValuePubSubType::createData() + { + return reinterpret_cast(new LongitudinalAccelerationValue()); + } + + void LongitudinalAccelerationValuePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool LongitudinalAccelerationValuePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + LongitudinalAccelerationValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + LongitudinalAccelerationValue::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || LongitudinalAccelerationValue::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValuePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValuePubSubTypes.h new file mode 100644 index 00000000000..2edc3e7443d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValuePubSubTypes.h @@ -0,0 +1,115 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LongitudinalAccelerationValuePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATIONVALUE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATIONVALUE_PUBSUBTYPES_H_ + +#include +#include + +#include "LongitudinalAccelerationValue.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated LongitudinalAccelerationValue is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace LongitudinalAccelerationValue_Constants + { + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type LongitudinalAccelerationValue defined by the user in the IDL file. + * @ingroup LONGITUDINALACCELERATIONVALUE + */ + class LongitudinalAccelerationValuePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef LongitudinalAccelerationValue type; + + eProsima_user_DllExport LongitudinalAccelerationValuePubSubType(); + + eProsima_user_DllExport virtual ~LongitudinalAccelerationValuePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) LongitudinalAccelerationValue(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATIONVALUE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainer.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainer.cxx new file mode 100644 index 00000000000..877548ce460 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainer.cxx @@ -0,0 +1,234 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LowFrequencyContainer.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "LowFrequencyContainer.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +etsi_its_cam_msgs::msg::LowFrequencyContainer::LowFrequencyContainer() +{ + // m_choice com.eprosima.idl.parser.typecode.PrimitiveTypeCode@4362d7df + m_choice = 0; + // m_basic_vehicle_container_low_frequency com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@66238be2 + + +} + +etsi_its_cam_msgs::msg::LowFrequencyContainer::~LowFrequencyContainer() +{ + +} + +etsi_its_cam_msgs::msg::LowFrequencyContainer::LowFrequencyContainer( + const LowFrequencyContainer& x) +{ + m_choice = x.m_choice; + m_basic_vehicle_container_low_frequency = x.m_basic_vehicle_container_low_frequency; +} + +etsi_its_cam_msgs::msg::LowFrequencyContainer::LowFrequencyContainer( + LowFrequencyContainer&& x) +{ + m_choice = x.m_choice; + m_basic_vehicle_container_low_frequency = std::move(x.m_basic_vehicle_container_low_frequency); +} + +etsi_its_cam_msgs::msg::LowFrequencyContainer& etsi_its_cam_msgs::msg::LowFrequencyContainer::operator =( + const LowFrequencyContainer& x) +{ + + m_choice = x.m_choice; + m_basic_vehicle_container_low_frequency = x.m_basic_vehicle_container_low_frequency; + + return *this; +} + +etsi_its_cam_msgs::msg::LowFrequencyContainer& etsi_its_cam_msgs::msg::LowFrequencyContainer::operator =( + LowFrequencyContainer&& x) +{ + + m_choice = x.m_choice; + m_basic_vehicle_container_low_frequency = std::move(x.m_basic_vehicle_container_low_frequency); + + return *this; +} + +bool etsi_its_cam_msgs::msg::LowFrequencyContainer::operator ==( + const LowFrequencyContainer& x) const +{ + + return (m_choice == x.m_choice && m_basic_vehicle_container_low_frequency == x.m_basic_vehicle_container_low_frequency); +} + +bool etsi_its_cam_msgs::msg::LowFrequencyContainer::operator !=( + const LowFrequencyContainer& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::LowFrequencyContainer::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::LowFrequencyContainer::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::LowFrequencyContainer& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency::getCdrSerializedSize(data.basic_vehicle_container_low_frequency(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::LowFrequencyContainer::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_choice; + scdr << m_basic_vehicle_container_low_frequency; + +} + +void etsi_its_cam_msgs::msg::LowFrequencyContainer::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_choice; + dcdr >> m_basic_vehicle_container_low_frequency; +} + +/*! + * @brief This function sets a value in member choice + * @param _choice New value for member choice + */ +void etsi_its_cam_msgs::msg::LowFrequencyContainer::choice( + uint8_t _choice) +{ + m_choice = _choice; +} + +/*! + * @brief This function returns the value of member choice + * @return Value of member choice + */ +uint8_t etsi_its_cam_msgs::msg::LowFrequencyContainer::choice() const +{ + return m_choice; +} + +/*! + * @brief This function returns a reference to member choice + * @return Reference to member choice + */ +uint8_t& etsi_its_cam_msgs::msg::LowFrequencyContainer::choice() +{ + return m_choice; +} + +/*! + * @brief This function copies the value in member basic_vehicle_container_low_frequency + * @param _basic_vehicle_container_low_frequency New value to be copied in member basic_vehicle_container_low_frequency + */ +void etsi_its_cam_msgs::msg::LowFrequencyContainer::basic_vehicle_container_low_frequency( + const etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency& _basic_vehicle_container_low_frequency) +{ + m_basic_vehicle_container_low_frequency = _basic_vehicle_container_low_frequency; +} + +/*! + * @brief This function moves the value in member basic_vehicle_container_low_frequency + * @param _basic_vehicle_container_low_frequency New value to be moved in member basic_vehicle_container_low_frequency + */ +void etsi_its_cam_msgs::msg::LowFrequencyContainer::basic_vehicle_container_low_frequency( + etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency&& _basic_vehicle_container_low_frequency) +{ + m_basic_vehicle_container_low_frequency = std::move(_basic_vehicle_container_low_frequency); +} + +/*! + * @brief This function returns a constant reference to member basic_vehicle_container_low_frequency + * @return Constant reference to member basic_vehicle_container_low_frequency + */ +const etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency& etsi_its_cam_msgs::msg::LowFrequencyContainer::basic_vehicle_container_low_frequency() const +{ + return m_basic_vehicle_container_low_frequency; +} + +/*! + * @brief This function returns a reference to member basic_vehicle_container_low_frequency + * @return Reference to member basic_vehicle_container_low_frequency + */ +etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency& etsi_its_cam_msgs::msg::LowFrequencyContainer::basic_vehicle_container_low_frequency() +{ + return m_basic_vehicle_container_low_frequency; +} + +size_t etsi_its_cam_msgs::msg::LowFrequencyContainer::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::LowFrequencyContainer::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::LowFrequencyContainer::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainer.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainer.h new file mode 100644 index 00000000000..999a96a40a8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainer.h @@ -0,0 +1,240 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LowFrequencyContainer.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LOWFREQUENCYCONTAINER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LOWFREQUENCYCONTAINER_H_ + +#include "BasicVehicleContainerLowFrequency.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(LowFrequencyContainer_SOURCE) +#define LowFrequencyContainer_DllAPI __declspec( dllexport ) +#else +#define LowFrequencyContainer_DllAPI __declspec( dllimport ) +#endif // LowFrequencyContainer_SOURCE +#else +#define LowFrequencyContainer_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define LowFrequencyContainer_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace LowFrequencyContainer_Constants { + const uint8_t CHOICE_BASIC_VEHICLE_CONTAINER_LOW_FREQUENCY = 0; + } // namespace LowFrequencyContainer_Constants + /*! + * @brief This class represents the structure LowFrequencyContainer defined by the user in the IDL file. + * @ingroup LOWFREQUENCYCONTAINER + */ + class LowFrequencyContainer + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport LowFrequencyContainer(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~LowFrequencyContainer(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::LowFrequencyContainer that will be copied. + */ + eProsima_user_DllExport LowFrequencyContainer( + const LowFrequencyContainer& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::LowFrequencyContainer that will be copied. + */ + eProsima_user_DllExport LowFrequencyContainer( + LowFrequencyContainer&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::LowFrequencyContainer that will be copied. + */ + eProsima_user_DllExport LowFrequencyContainer& operator =( + const LowFrequencyContainer& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::LowFrequencyContainer that will be copied. + */ + eProsima_user_DllExport LowFrequencyContainer& operator =( + LowFrequencyContainer&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::LowFrequencyContainer object to compare. + */ + eProsima_user_DllExport bool operator ==( + const LowFrequencyContainer& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::LowFrequencyContainer object to compare. + */ + eProsima_user_DllExport bool operator !=( + const LowFrequencyContainer& x) const; + + /*! + * @brief This function sets a value in member choice + * @param _choice New value for member choice + */ + eProsima_user_DllExport void choice( + uint8_t _choice); + + /*! + * @brief This function returns the value of member choice + * @return Value of member choice + */ + eProsima_user_DllExport uint8_t choice() const; + + /*! + * @brief This function returns a reference to member choice + * @return Reference to member choice + */ + eProsima_user_DllExport uint8_t& choice(); + + /*! + * @brief This function copies the value in member basic_vehicle_container_low_frequency + * @param _basic_vehicle_container_low_frequency New value to be copied in member basic_vehicle_container_low_frequency + */ + eProsima_user_DllExport void basic_vehicle_container_low_frequency( + const etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency& _basic_vehicle_container_low_frequency); + + /*! + * @brief This function moves the value in member basic_vehicle_container_low_frequency + * @param _basic_vehicle_container_low_frequency New value to be moved in member basic_vehicle_container_low_frequency + */ + eProsima_user_DllExport void basic_vehicle_container_low_frequency( + etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency&& _basic_vehicle_container_low_frequency); + + /*! + * @brief This function returns a constant reference to member basic_vehicle_container_low_frequency + * @return Constant reference to member basic_vehicle_container_low_frequency + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency& basic_vehicle_container_low_frequency() const; + + /*! + * @brief This function returns a reference to member basic_vehicle_container_low_frequency + * @return Reference to member basic_vehicle_container_low_frequency + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency& basic_vehicle_container_low_frequency(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::LowFrequencyContainer& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_choice; + etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency m_basic_vehicle_container_low_frequency; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LOWFREQUENCYCONTAINER_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainerPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainerPubSubTypes.cxx new file mode 100644 index 00000000000..7a9ec3027c1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainerPubSubTypes.cxx @@ -0,0 +1,178 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file LowFrequencyContainerPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "LowFrequencyContainerPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace LowFrequencyContainer_Constants { + } //End of namespace LowFrequencyContainer_Constants + LowFrequencyContainerPubSubType::LowFrequencyContainerPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::LowFrequencyContainer_"); + auto type_size = LowFrequencyContainer::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = LowFrequencyContainer::isKeyDefined(); + size_t keyLength = LowFrequencyContainer::getKeyMaxCdrSerializedSize() > 16 ? + LowFrequencyContainer::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + LowFrequencyContainerPubSubType::~LowFrequencyContainerPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool LowFrequencyContainerPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + LowFrequencyContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool LowFrequencyContainerPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + LowFrequencyContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function LowFrequencyContainerPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* LowFrequencyContainerPubSubType::createData() + { + return reinterpret_cast(new LowFrequencyContainer()); + } + + void LowFrequencyContainerPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool LowFrequencyContainerPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + LowFrequencyContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + LowFrequencyContainer::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || LowFrequencyContainer::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/types/AckermannDriveStampedPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainerPubSubTypes.h similarity index 77% rename from LibCarla/source/carla/ros2/types/AckermannDriveStampedPubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainerPubSubTypes.h index 84240bc7cbd..1f7ba2ac1a0 100644 --- a/LibCarla/source/carla/ros2/types/AckermannDriveStampedPubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainerPubSubTypes.h @@ -13,47 +13,46 @@ // limitations under the License. /*! - * @file AckermannDriveStampedPubSubTypes.h + * @file LowFrequencyContainerPubSubTypes.h * This header file contains the declaration of the serialization functions. * * This file was generated by the tool fastcdrgen. */ -#ifndef _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPED_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPED_PUBSUBTYPES_H_ +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LOWFREQUENCYCONTAINER_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LOWFREQUENCYCONTAINER_PUBSUBTYPES_H_ #include #include -#include "AckermannDriveStamped.h" - -#include "AckermannDrivePubSubTypes.h" -#include "HeaderPubSubTypes.h" +#include "LowFrequencyContainer.h" #if !defined(GEN_API_VER) || (GEN_API_VER != 1) #error \ - Generated AckermannDriveStamped is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. + Generated LowFrequencyContainer is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. #endif // GEN_API_VER -namespace ackermann_msgs +namespace etsi_its_cam_msgs { namespace msg { - + namespace LowFrequencyContainer_Constants + { + } /*! - * @brief This class represents the TopicDataType of the type AckermannDriveStamped defined by the user in the IDL file. - * @ingroup AckermannDriveStamped + * @brief This class represents the TopicDataType of the type LowFrequencyContainer defined by the user in the IDL file. + * @ingroup LOWFREQUENCYCONTAINER */ - class AckermannDriveStampedPubSubType : public eprosima::fastdds::dds::TopicDataType + class LowFrequencyContainerPubSubType : public eprosima::fastdds::dds::TopicDataType { public: - typedef AckermannDriveStamped type; + typedef LowFrequencyContainer type; - eProsima_user_DllExport AckermannDriveStampedPubSubType(); + eProsima_user_DllExport LowFrequencyContainerPubSubType(); - eProsima_user_DllExport virtual ~AckermannDriveStampedPubSubType() override; + eProsima_user_DllExport virtual ~LowFrequencyContainerPubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -104,10 +103,8 @@ namespace ackermann_msgs MD5 m_md5; unsigned char* m_keyBuffer; - }; } } -#endif // _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPED_PUBSUBTYPES_H_ - +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LOWFREQUENCYCONTAINER_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTime.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTime.cxx new file mode 100644 index 00000000000..7dd529e1aaa --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTime.cxx @@ -0,0 +1,187 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PathDeltaTime.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "PathDeltaTime.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + +etsi_its_cam_msgs::msg::PathDeltaTime::PathDeltaTime() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@60afd40d + m_value = 0; + +} + +etsi_its_cam_msgs::msg::PathDeltaTime::~PathDeltaTime() +{ +} + +etsi_its_cam_msgs::msg::PathDeltaTime::PathDeltaTime( + const PathDeltaTime& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::PathDeltaTime::PathDeltaTime( + PathDeltaTime&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::PathDeltaTime& etsi_its_cam_msgs::msg::PathDeltaTime::operator =( + const PathDeltaTime& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::PathDeltaTime& etsi_its_cam_msgs::msg::PathDeltaTime::operator =( + PathDeltaTime&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::PathDeltaTime::operator ==( + const PathDeltaTime& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::PathDeltaTime::operator !=( + const PathDeltaTime& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::PathDeltaTime::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::PathDeltaTime::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::PathDeltaTime& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::PathDeltaTime::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::PathDeltaTime::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::PathDeltaTime::value( + uint16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint16_t etsi_its_cam_msgs::msg::PathDeltaTime::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint16_t& etsi_its_cam_msgs::msg::PathDeltaTime::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::PathDeltaTime::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::PathDeltaTime::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::PathDeltaTime::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTime.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTime.h new file mode 100644 index 00000000000..c851458eb1b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTime.h @@ -0,0 +1,215 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PathDeltaTime.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHDELTATIME_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHDELTATIME_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(PathDeltaTime_SOURCE) +#define PathDeltaTime_DllAPI __declspec( dllexport ) +#else +#define PathDeltaTime_DllAPI __declspec( dllimport ) +#endif // PathDeltaTime_SOURCE +#else +#define PathDeltaTime_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define PathDeltaTime_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace PathDeltaTime_Constants { + const uint16_t MIN = 1; + const uint16_t MAX = 65535; + const uint16_t TEN_MILLI_SECONDS_IN_PAST = 1; + } // namespace PathDeltaTime_Constants + /*! + * @brief This class represents the structure PathDeltaTime defined by the user in the IDL file. + * @ingroup PATHDELTATIME + */ + class PathDeltaTime + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport PathDeltaTime(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~PathDeltaTime(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::PathDeltaTime that will be copied. + */ + eProsima_user_DllExport PathDeltaTime( + const PathDeltaTime& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::PathDeltaTime that will be copied. + */ + eProsima_user_DllExport PathDeltaTime( + PathDeltaTime&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::PathDeltaTime that will be copied. + */ + eProsima_user_DllExport PathDeltaTime& operator =( + const PathDeltaTime& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::PathDeltaTime that will be copied. + */ + eProsima_user_DllExport PathDeltaTime& operator =( + PathDeltaTime&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::PathDeltaTime object to compare. + */ + eProsima_user_DllExport bool operator ==( + const PathDeltaTime& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::PathDeltaTime object to compare. + */ + eProsima_user_DllExport bool operator !=( + const PathDeltaTime& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint16_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint16_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint16_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::PathDeltaTime& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint16_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHDELTATIME_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTimePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTimePubSubTypes.cxx new file mode 100644 index 00000000000..446b7c19fce --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTimePubSubTypes.cxx @@ -0,0 +1,182 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PathDeltaTimePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "PathDeltaTimePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace PathDeltaTime_Constants { + + + + + } //End of namespace PathDeltaTime_Constants + PathDeltaTimePubSubType::PathDeltaTimePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::PathDeltaTime_"); + auto type_size = PathDeltaTime::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = PathDeltaTime::isKeyDefined(); + size_t keyLength = PathDeltaTime::getKeyMaxCdrSerializedSize() > 16 ? + PathDeltaTime::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + PathDeltaTimePubSubType::~PathDeltaTimePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool PathDeltaTimePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + PathDeltaTime* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool PathDeltaTimePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + PathDeltaTime* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function PathDeltaTimePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* PathDeltaTimePubSubType::createData() + { + return reinterpret_cast(new PathDeltaTime()); + } + + void PathDeltaTimePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool PathDeltaTimePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + PathDeltaTime* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + PathDeltaTime::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || PathDeltaTime::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTimePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTimePubSubTypes.h new file mode 100644 index 00000000000..4db08bacead --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTimePubSubTypes.h @@ -0,0 +1,113 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PathDeltaTimePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHDELTATIME_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHDELTATIME_PUBSUBTYPES_H_ + +#include +#include + +#include "PathDeltaTime.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated PathDeltaTime is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace PathDeltaTime_Constants + { + + + + } + /*! + * @brief This class represents the TopicDataType of the type PathDeltaTime defined by the user in the IDL file. + * @ingroup PATHDELTATIME + */ + class PathDeltaTimePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef PathDeltaTime type; + + eProsima_user_DllExport PathDeltaTimePubSubType(); + + eProsima_user_DllExport virtual ~PathDeltaTimePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) PathDeltaTime(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHDELTATIME_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistory.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistory.cxx new file mode 100644 index 00000000000..01b50a9a696 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistory.cxx @@ -0,0 +1,201 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PathHistory.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "PathHistory.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + +etsi_its_cam_msgs::msg::PathHistory::PathHistory() +{ + // m_array com.eprosima.idl.parser.typecode.SequenceTypeCode@1d572e62 + + +} + +etsi_its_cam_msgs::msg::PathHistory::~PathHistory() +{ +} + +etsi_its_cam_msgs::msg::PathHistory::PathHistory( + const PathHistory& x) +{ + m_array = x.m_array; +} + +etsi_its_cam_msgs::msg::PathHistory::PathHistory( + PathHistory&& x) +{ + m_array = std::move(x.m_array); +} + +etsi_its_cam_msgs::msg::PathHistory& etsi_its_cam_msgs::msg::PathHistory::operator =( + const PathHistory& x) +{ + + m_array = x.m_array; + + return *this; +} + +etsi_its_cam_msgs::msg::PathHistory& etsi_its_cam_msgs::msg::PathHistory::operator =( + PathHistory&& x) +{ + + m_array = std::move(x.m_array); + + return *this; +} + +bool etsi_its_cam_msgs::msg::PathHistory::operator ==( + const PathHistory& x) const +{ + + return (m_array == x.m_array); +} + +bool etsi_its_cam_msgs::msg::PathHistory::operator !=( + const PathHistory& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::PathHistory::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < 100; ++a) + { + current_alignment += etsi_its_cam_msgs::msg::PathPoint::getMaxCdrSerializedSize(current_alignment);} + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::PathHistory::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::PathHistory& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < data.array().size(); ++a) + { + current_alignment += etsi_its_cam_msgs::msg::PathPoint::getCdrSerializedSize(data.array().at(a), current_alignment);} + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::PathHistory::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_array; +} + +void etsi_its_cam_msgs::msg::PathHistory::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_array;} + +/*! + * @brief This function copies the value in member array + * @param _array New value to be copied in member array + */ +void etsi_its_cam_msgs::msg::PathHistory::array( + const std::vector& _array) +{ + m_array = _array; +} + +/*! + * @brief This function moves the value in member array + * @param _array New value to be moved in member array + */ +void etsi_its_cam_msgs::msg::PathHistory::array( + std::vector&& _array) +{ + m_array = std::move(_array); +} + +/*! + * @brief This function returns a constant reference to member array + * @return Constant reference to member array + */ +const std::vector& etsi_its_cam_msgs::msg::PathHistory::array() const +{ + return m_array; +} + +/*! + * @brief This function returns a reference to member array + * @return Reference to member array + */ +std::vector& etsi_its_cam_msgs::msg::PathHistory::array() +{ + return m_array; +} + +size_t etsi_its_cam_msgs::msg::PathHistory::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::PathHistory::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::PathHistory::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistory.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistory.h new file mode 100644 index 00000000000..d15c6e2f7f8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistory.h @@ -0,0 +1,221 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PathHistory.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHHISTORY_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHHISTORY_H_ + +#include "PathPoint.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(PathHistory_SOURCE) +#define PathHistory_DllAPI __declspec( dllexport ) +#else +#define PathHistory_DllAPI __declspec( dllimport ) +#endif // PathHistory_SOURCE +#else +#define PathHistory_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define PathHistory_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace PathHistory_Constants { + const uint8_t MIN_SIZE = 0; + const uint8_t MAX_SIZE = 40; + } // namespace PathHistory_Constants + /*! + * @brief This class represents the structure PathHistory defined by the user in the IDL file. + * @ingroup PATHHISTORY + */ + class PathHistory + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport PathHistory(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~PathHistory(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::PathHistory that will be copied. + */ + eProsima_user_DllExport PathHistory( + const PathHistory& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::PathHistory that will be copied. + */ + eProsima_user_DllExport PathHistory( + PathHistory&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::PathHistory that will be copied. + */ + eProsima_user_DllExport PathHistory& operator =( + const PathHistory& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::PathHistory that will be copied. + */ + eProsima_user_DllExport PathHistory& operator =( + PathHistory&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::PathHistory object to compare. + */ + eProsima_user_DllExport bool operator ==( + const PathHistory& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::PathHistory object to compare. + */ + eProsima_user_DllExport bool operator !=( + const PathHistory& x) const; + + /*! + * @brief This function copies the value in member array + * @param _array New value to be copied in member array + */ + eProsima_user_DllExport void array( + const std::vector& _array); + + /*! + * @brief This function moves the value in member array + * @param _array New value to be moved in member array + */ + eProsima_user_DllExport void array( + std::vector&& _array); + + /*! + * @brief This function returns a constant reference to member array + * @return Constant reference to member array + */ + eProsima_user_DllExport const std::vector& array() const; + + /*! + * @brief This function returns a reference to member array + * @return Reference to member array + */ + eProsima_user_DllExport std::vector& array(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::PathHistory& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std::vector m_array; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHHISTORY_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistoryPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistoryPubSubTypes.cxx new file mode 100644 index 00000000000..ee1bafed3ef --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistoryPubSubTypes.cxx @@ -0,0 +1,181 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PathHistoryPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "PathHistoryPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace PathHistory_Constants { + + + + } //End of namespace PathHistory_Constants + PathHistoryPubSubType::PathHistoryPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::PathHistory_"); + auto type_size = PathHistory::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = PathHistory::isKeyDefined(); + size_t keyLength = PathHistory::getKeyMaxCdrSerializedSize() > 16 ? + PathHistory::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + PathHistoryPubSubType::~PathHistoryPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool PathHistoryPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + PathHistory* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool PathHistoryPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + PathHistory* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function PathHistoryPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* PathHistoryPubSubType::createData() + { + return reinterpret_cast(new PathHistory()); + } + + void PathHistoryPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool PathHistoryPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + PathHistory* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + PathHistory::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || PathHistory::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/types/ImuPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistoryPubSubTypes.h similarity index 77% rename from LibCarla/source/carla/ros2/types/ImuPubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistoryPubSubTypes.h index 1dcca34f3e1..e86969c298b 100644 --- a/LibCarla/source/carla/ros2/types/ImuPubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistoryPubSubTypes.h @@ -13,48 +13,48 @@ // limitations under the License. /*! - * @file ImuPubSubTypes.h + * @file PathHistoryPubSubTypes.h * This header file contains the declaration of the serialization functions. * * This file was generated by the tool fastcdrgen. */ -#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMU_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMU_PUBSUBTYPES_H_ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHHISTORY_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHHISTORY_PUBSUBTYPES_H_ #include #include -#include "Imu.h" - -#include "Vector3PubSubTypes.h" -#include "QuaternionPubSubTypes.h" -#include "HeaderPubSubTypes.h" +#include "PathHistory.h" #if !defined(GEN_API_VER) || (GEN_API_VER != 1) #error \ - Generated Imu is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. + Generated PathHistory is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. #endif // GEN_API_VER -namespace sensor_msgs +namespace etsi_its_cam_msgs { namespace msg { - typedef std::array sensor_msgs__Imu__double_array_9; + namespace PathHistory_Constants + { + + } /*! - * @brief This class represents the TopicDataType of the type Imu defined by the user in the IDL file. - * @ingroup IMU + * @brief This class represents the TopicDataType of the type PathHistory defined by the user in the IDL file. + * @ingroup PATHHISTORY */ - class ImuPubSubType : public eprosima::fastdds::dds::TopicDataType + class PathHistoryPubSubType : public eprosima::fastdds::dds::TopicDataType { public: - typedef Imu type; + typedef PathHistory type; - eProsima_user_DllExport ImuPubSubType(); + eProsima_user_DllExport PathHistoryPubSubType(); - eProsima_user_DllExport virtual ~ImuPubSubType() override; + eProsima_user_DllExport virtual ~PathHistoryPubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -102,10 +102,11 @@ namespace sensor_msgs } #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; unsigned char* m_keyBuffer; }; } } -#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMU_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHHISTORY_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPoint.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPoint.cxx new file mode 100644 index 00000000000..d8ed47d4519 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPoint.cxx @@ -0,0 +1,281 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PathPoint.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "PathPoint.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::PathPoint::PathPoint() +{ + // m_path_position com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@5167268 + + // m_path_delta_time com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@1cfd1875 + + // m_path_delta_time_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@28c0b664 + m_path_delta_time_is_present = false; + +} + +etsi_its_cam_msgs::msg::PathPoint::~PathPoint() +{ + + +} + +etsi_its_cam_msgs::msg::PathPoint::PathPoint( + const PathPoint& x) +{ + m_path_position = x.m_path_position; + m_path_delta_time = x.m_path_delta_time; + m_path_delta_time_is_present = x.m_path_delta_time_is_present; +} + +etsi_its_cam_msgs::msg::PathPoint::PathPoint( + PathPoint&& x) +{ + m_path_position = std::move(x.m_path_position); + m_path_delta_time = std::move(x.m_path_delta_time); + m_path_delta_time_is_present = x.m_path_delta_time_is_present; +} + +etsi_its_cam_msgs::msg::PathPoint& etsi_its_cam_msgs::msg::PathPoint::operator =( + const PathPoint& x) +{ + + m_path_position = x.m_path_position; + m_path_delta_time = x.m_path_delta_time; + m_path_delta_time_is_present = x.m_path_delta_time_is_present; + + return *this; +} + +etsi_its_cam_msgs::msg::PathPoint& etsi_its_cam_msgs::msg::PathPoint::operator =( + PathPoint&& x) +{ + + m_path_position = std::move(x.m_path_position); + m_path_delta_time = std::move(x.m_path_delta_time); + m_path_delta_time_is_present = x.m_path_delta_time_is_present; + + return *this; +} + +bool etsi_its_cam_msgs::msg::PathPoint::operator ==( + const PathPoint& x) const +{ + + return (m_path_position == x.m_path_position && m_path_delta_time == x.m_path_delta_time && m_path_delta_time_is_present == x.m_path_delta_time_is_present); +} + +bool etsi_its_cam_msgs::msg::PathPoint::operator !=( + const PathPoint& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::PathPoint::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::DeltaReferencePosition::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::PathDeltaTime::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::PathPoint::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::PathPoint& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::DeltaReferencePosition::getCdrSerializedSize(data.path_position(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::PathDeltaTime::getCdrSerializedSize(data.path_delta_time(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::PathPoint::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_path_position; + scdr << m_path_delta_time; + scdr << m_path_delta_time_is_present; + +} + +void etsi_its_cam_msgs::msg::PathPoint::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_path_position; + dcdr >> m_path_delta_time; + dcdr >> m_path_delta_time_is_present; +} + +/*! + * @brief This function copies the value in member path_position + * @param _path_position New value to be copied in member path_position + */ +void etsi_its_cam_msgs::msg::PathPoint::path_position( + const etsi_its_cam_msgs::msg::DeltaReferencePosition& _path_position) +{ + m_path_position = _path_position; +} + +/*! + * @brief This function moves the value in member path_position + * @param _path_position New value to be moved in member path_position + */ +void etsi_its_cam_msgs::msg::PathPoint::path_position( + etsi_its_cam_msgs::msg::DeltaReferencePosition&& _path_position) +{ + m_path_position = std::move(_path_position); +} + +/*! + * @brief This function returns a constant reference to member path_position + * @return Constant reference to member path_position + */ +const etsi_its_cam_msgs::msg::DeltaReferencePosition& etsi_its_cam_msgs::msg::PathPoint::path_position() const +{ + return m_path_position; +} + +/*! + * @brief This function returns a reference to member path_position + * @return Reference to member path_position + */ +etsi_its_cam_msgs::msg::DeltaReferencePosition& etsi_its_cam_msgs::msg::PathPoint::path_position() +{ + return m_path_position; +} +/*! + * @brief This function copies the value in member path_delta_time + * @param _path_delta_time New value to be copied in member path_delta_time + */ +void etsi_its_cam_msgs::msg::PathPoint::path_delta_time( + const etsi_its_cam_msgs::msg::PathDeltaTime& _path_delta_time) +{ + m_path_delta_time = _path_delta_time; +} + +/*! + * @brief This function moves the value in member path_delta_time + * @param _path_delta_time New value to be moved in member path_delta_time + */ +void etsi_its_cam_msgs::msg::PathPoint::path_delta_time( + etsi_its_cam_msgs::msg::PathDeltaTime&& _path_delta_time) +{ + m_path_delta_time = std::move(_path_delta_time); +} + +/*! + * @brief This function returns a constant reference to member path_delta_time + * @return Constant reference to member path_delta_time + */ +const etsi_its_cam_msgs::msg::PathDeltaTime& etsi_its_cam_msgs::msg::PathPoint::path_delta_time() const +{ + return m_path_delta_time; +} + +/*! + * @brief This function returns a reference to member path_delta_time + * @return Reference to member path_delta_time + */ +etsi_its_cam_msgs::msg::PathDeltaTime& etsi_its_cam_msgs::msg::PathPoint::path_delta_time() +{ + return m_path_delta_time; +} +/*! + * @brief This function sets a value in member path_delta_time_is_present + * @param _path_delta_time_is_present New value for member path_delta_time_is_present + */ +void etsi_its_cam_msgs::msg::PathPoint::path_delta_time_is_present( + bool _path_delta_time_is_present) +{ + m_path_delta_time_is_present = _path_delta_time_is_present; +} + +/*! + * @brief This function returns the value of member path_delta_time_is_present + * @return Value of member path_delta_time_is_present + */ +bool etsi_its_cam_msgs::msg::PathPoint::path_delta_time_is_present() const +{ + return m_path_delta_time_is_present; +} + +/*! + * @brief This function returns a reference to member path_delta_time_is_present + * @return Reference to member path_delta_time_is_present + */ +bool& etsi_its_cam_msgs::msg::PathPoint::path_delta_time_is_present() +{ + return m_path_delta_time_is_present; +} + + +size_t etsi_its_cam_msgs::msg::PathPoint::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::PathPoint::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::PathPoint::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPoint.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPoint.h new file mode 100644 index 00000000000..439be91762b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPoint.h @@ -0,0 +1,264 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PathPoint.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHPOINT_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHPOINT_H_ + +#include "DeltaReferencePosition.h" +#include "PathDeltaTime.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(PathPoint_SOURCE) +#define PathPoint_DllAPI __declspec( dllexport ) +#else +#define PathPoint_DllAPI __declspec( dllimport ) +#endif // PathPoint_SOURCE +#else +#define PathPoint_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define PathPoint_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure PathPoint defined by the user in the IDL file. + * @ingroup PATHPOINT + */ + class PathPoint + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport PathPoint(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~PathPoint(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::PathPoint that will be copied. + */ + eProsima_user_DllExport PathPoint( + const PathPoint& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::PathPoint that will be copied. + */ + eProsima_user_DllExport PathPoint( + PathPoint&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::PathPoint that will be copied. + */ + eProsima_user_DllExport PathPoint& operator =( + const PathPoint& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::PathPoint that will be copied. + */ + eProsima_user_DllExport PathPoint& operator =( + PathPoint&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::PathPoint object to compare. + */ + eProsima_user_DllExport bool operator ==( + const PathPoint& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::PathPoint object to compare. + */ + eProsima_user_DllExport bool operator !=( + const PathPoint& x) const; + + /*! + * @brief This function copies the value in member path_position + * @param _path_position New value to be copied in member path_position + */ + eProsima_user_DllExport void path_position( + const etsi_its_cam_msgs::msg::DeltaReferencePosition& _path_position); + + /*! + * @brief This function moves the value in member path_position + * @param _path_position New value to be moved in member path_position + */ + eProsima_user_DllExport void path_position( + etsi_its_cam_msgs::msg::DeltaReferencePosition&& _path_position); + + /*! + * @brief This function returns a constant reference to member path_position + * @return Constant reference to member path_position + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::DeltaReferencePosition& path_position() const; + + /*! + * @brief This function returns a reference to member path_position + * @return Reference to member path_position + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::DeltaReferencePosition& path_position(); + /*! + * @brief This function copies the value in member path_delta_time + * @param _path_delta_time New value to be copied in member path_delta_time + */ + eProsima_user_DllExport void path_delta_time( + const etsi_its_cam_msgs::msg::PathDeltaTime& _path_delta_time); + + /*! + * @brief This function moves the value in member path_delta_time + * @param _path_delta_time New value to be moved in member path_delta_time + */ + eProsima_user_DllExport void path_delta_time( + etsi_its_cam_msgs::msg::PathDeltaTime&& _path_delta_time); + + /*! + * @brief This function returns a constant reference to member path_delta_time + * @return Constant reference to member path_delta_time + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::PathDeltaTime& path_delta_time() const; + + /*! + * @brief This function returns a reference to member path_delta_time + * @return Reference to member path_delta_time + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::PathDeltaTime& path_delta_time(); + /*! + * @brief This function sets a value in member path_delta_time_is_present + * @param _path_delta_time_is_present New value for member path_delta_time_is_present + */ + eProsima_user_DllExport void path_delta_time_is_present( + bool _path_delta_time_is_present); + + /*! + * @brief This function returns the value of member path_delta_time_is_present + * @return Value of member path_delta_time_is_present + */ + eProsima_user_DllExport bool path_delta_time_is_present() const; + + /*! + * @brief This function returns a reference to member path_delta_time_is_present + * @return Reference to member path_delta_time_is_present + */ + eProsima_user_DllExport bool& path_delta_time_is_present(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::PathPoint& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::DeltaReferencePosition m_path_position; + etsi_its_cam_msgs::msg::PathDeltaTime m_path_delta_time; + bool m_path_delta_time_is_present; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHPOINT_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPointPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPointPubSubTypes.cxx new file mode 100644 index 00000000000..956d7d1f9b2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPointPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PathPointPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "PathPointPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + PathPointPubSubType::PathPointPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::PathPoint_"); + auto type_size = PathPoint::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = PathPoint::isKeyDefined(); + size_t keyLength = PathPoint::getKeyMaxCdrSerializedSize() > 16 ? + PathPoint::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + PathPointPubSubType::~PathPointPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool PathPointPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + PathPoint* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool PathPointPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + PathPoint* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function PathPointPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* PathPointPubSubType::createData() + { + return reinterpret_cast(new PathPoint()); + } + + void PathPointPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool PathPointPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + PathPoint* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + PathPoint::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || PathPoint::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPointPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPointPubSubTypes.h new file mode 100644 index 00000000000..f7d91879e92 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPointPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PathPointPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHPOINT_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHPOINT_PUBSUBTYPES_H_ + +#include +#include + +#include "PathPoint.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated PathPoint is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type PathPoint defined by the user in the IDL file. + * @ingroup PATHPOINT + */ + class PathPointPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef PathPoint type; + + eProsima_user_DllExport PathPointPubSubType(); + + eProsima_user_DllExport virtual ~PathPointPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) PathPoint(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHPOINT_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClass.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClass.cxx new file mode 100644 index 00000000000..931268e7ed3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClass.cxx @@ -0,0 +1,189 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PerformanceClass.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "PerformanceClass.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + +etsi_its_cam_msgs::msg::PerformanceClass::PerformanceClass() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@77128dab + m_value = 0; + +} + +etsi_its_cam_msgs::msg::PerformanceClass::~PerformanceClass() +{ +} + +etsi_its_cam_msgs::msg::PerformanceClass::PerformanceClass( + const PerformanceClass& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::PerformanceClass::PerformanceClass( + PerformanceClass&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::PerformanceClass& etsi_its_cam_msgs::msg::PerformanceClass::operator =( + const PerformanceClass& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::PerformanceClass& etsi_its_cam_msgs::msg::PerformanceClass::operator =( + PerformanceClass&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::PerformanceClass::operator ==( + const PerformanceClass& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::PerformanceClass::operator !=( + const PerformanceClass& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::PerformanceClass::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::PerformanceClass::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::PerformanceClass& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::PerformanceClass::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::PerformanceClass::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::PerformanceClass::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::PerformanceClass::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::PerformanceClass::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::PerformanceClass::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::PerformanceClass::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::PerformanceClass::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/types/Time.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClass.h similarity index 59% rename from LibCarla/source/carla/ros2/types/Time.h rename to LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClass.h index 216907bfda2..ca6a0f130ea 100644 --- a/LibCarla/source/carla/ros2/types/Time.h +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClass.h @@ -13,18 +13,16 @@ // limitations under the License. /*! - * @file Time.h + * @file PerformanceClass.h * This header file contains the declaration of the described types in the IDL file. * * This file was generated by the tool gen. */ -#ifndef _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIME_H_ -#define _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIME_H_ +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PERFORMANCECLASS_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PERFORMANCECLASS_H_ -#include - #include #include #include @@ -44,16 +42,16 @@ #if defined(_WIN32) #if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(Time_SOURCE) -#define Time_DllAPI __declspec( dllexport ) +#if defined(PerformanceClass_SOURCE) +#define PerformanceClass_DllAPI __declspec( dllexport ) #else -#define Time_DllAPI __declspec( dllimport ) -#endif // Time_SOURCE +#define PerformanceClass_DllAPI __declspec( dllimport ) +#endif // PerformanceClass_SOURCE #else -#define Time_DllAPI +#define PerformanceClass_DllAPI #endif // EPROSIMA_USER_DLL_EXPORT #else -#define Time_DllAPI +#define PerformanceClass_DllAPI #endif // _WIN32 namespace eprosima { @@ -62,112 +60,102 @@ class Cdr; } // namespace fastcdr } // namespace eprosima -namespace builtin_interfaces { + +namespace etsi_its_cam_msgs { namespace msg { + namespace PerformanceClass_Constants { + const uint8_t MIN = 0; + const uint8_t MAX = 7; + const uint8_t UNAVAILABLE = 0; + const uint8_t PERFORMANCE_CLASS_A = 1; + const uint8_t PERFORMANCE_CLASS_B = 2; + } // namespace PerformanceClass_Constants /*! - * @brief This class represents the structure Time defined by the user in the IDL file. - * @ingroup TIME + * @brief This class represents the structure PerformanceClass defined by the user in the IDL file. + * @ingroup PERFORMANCECLASS */ - class Time + class PerformanceClass { public: /*! * @brief Default constructor. */ - eProsima_user_DllExport Time(); + eProsima_user_DllExport PerformanceClass(); /*! * @brief Default destructor. */ - eProsima_user_DllExport ~Time(); + eProsima_user_DllExport ~PerformanceClass(); /*! * @brief Copy constructor. - * @param x Reference to the object builtin_interfaces::msg::Time that will be copied. + * @param x Reference to the object etsi_its_cam_msgs::msg::PerformanceClass that will be copied. */ - eProsima_user_DllExport Time( - const Time& x); + eProsima_user_DllExport PerformanceClass( + const PerformanceClass& x); /*! * @brief Move constructor. - * @param x Reference to the object builtin_interfaces::msg::Time that will be copied. + * @param x Reference to the object etsi_its_cam_msgs::msg::PerformanceClass that will be copied. */ - eProsima_user_DllExport Time( - Time&& x) noexcept; + eProsima_user_DllExport PerformanceClass( + PerformanceClass&& x); /*! * @brief Copy assignment. - * @param x Reference to the object builtin_interfaces::msg::Time that will be copied. + * @param x Reference to the object etsi_its_cam_msgs::msg::PerformanceClass that will be copied. */ - eProsima_user_DllExport Time& operator =( - const Time& x); + eProsima_user_DllExport PerformanceClass& operator =( + const PerformanceClass& x); /*! * @brief Move assignment. - * @param x Reference to the object builtin_interfaces::msg::Time that will be copied. + * @param x Reference to the object etsi_its_cam_msgs::msg::PerformanceClass that will be copied. */ - eProsima_user_DllExport Time& operator =( - Time&& x) noexcept; + eProsima_user_DllExport PerformanceClass& operator =( + PerformanceClass&& x); /*! * @brief Comparison operator. - * @param x builtin_interfaces::msg::Time object to compare. + * @param x etsi_its_cam_msgs::msg::PerformanceClass object to compare. */ eProsima_user_DllExport bool operator ==( - const Time& x) const; + const PerformanceClass& x) const; /*! * @brief Comparison operator. - * @param x builtin_interfaces::msg::Time object to compare. + * @param x etsi_its_cam_msgs::msg::PerformanceClass object to compare. */ eProsima_user_DllExport bool operator !=( - const Time& x) const; - - /*! - * @brief This function sets a value in member sec - * @param _sec New value for member sec - */ - eProsima_user_DllExport void sec( - int32_t _sec); + const PerformanceClass& x) const; /*! - * @brief This function returns the value of member sec - * @return Value of member sec + * @brief This function sets a value in member value + * @param _value New value for member value */ - eProsima_user_DllExport int32_t sec() const; + eProsima_user_DllExport void value( + uint8_t _value); /*! - * @brief This function returns a reference to member sec - * @return Reference to member sec + * @brief This function returns the value of member value + * @return Value of member value */ - eProsima_user_DllExport int32_t& sec(); + eProsima_user_DllExport uint8_t value() const; /*! - * @brief This function sets a value in member nanosec - * @param _nanosec New value for member nanosec + * @brief This function returns a reference to member value + * @return Reference to member value */ - eProsima_user_DllExport void nanosec( - uint32_t _nanosec); + eProsima_user_DllExport uint8_t& value(); - /*! - * @brief This function returns the value of member nanosec - * @return Value of member nanosec - */ - eProsima_user_DllExport uint32_t nanosec() const; /*! - * @brief This function returns a reference to member nanosec - * @return Reference to member nanosec + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. */ - eProsima_user_DllExport uint32_t& nanosec(); - - /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -178,9 +166,10 @@ namespace builtin_interfaces { * @return Serialized size. */ eProsima_user_DllExport static size_t getCdrSerializedSize( - const builtin_interfaces::msg::Time& data, + const etsi_its_cam_msgs::msg::PerformanceClass& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -195,6 +184,8 @@ namespace builtin_interfaces { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -217,10 +208,10 @@ namespace builtin_interfaces { eprosima::fastcdr::Cdr& cdr) const; private: - int32_t m_sec; - uint32_t m_nanosec; + + uint8_t m_value; }; } // namespace msg -} // namespace builtin_interfaces +} // namespace etsi_its_cam_msgs -#endif // _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIME_H_ +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PERFORMANCECLASS_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClassPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClassPubSubTypes.cxx new file mode 100644 index 00000000000..73bfb60a691 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClassPubSubTypes.cxx @@ -0,0 +1,184 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PerformanceClassPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "PerformanceClassPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace PerformanceClass_Constants { + + + + + + + } //End of namespace PerformanceClass_Constants + PerformanceClassPubSubType::PerformanceClassPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::PerformanceClass_"); + auto type_size = PerformanceClass::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = PerformanceClass::isKeyDefined(); + size_t keyLength = PerformanceClass::getKeyMaxCdrSerializedSize() > 16 ? + PerformanceClass::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + PerformanceClassPubSubType::~PerformanceClassPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool PerformanceClassPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + PerformanceClass* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool PerformanceClassPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + PerformanceClass* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function PerformanceClassPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* PerformanceClassPubSubType::createData() + { + return reinterpret_cast(new PerformanceClass()); + } + + void PerformanceClassPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool PerformanceClassPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + PerformanceClass* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + PerformanceClass::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || PerformanceClass::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClassPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClassPubSubTypes.h new file mode 100644 index 00000000000..4e8945ba55a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClassPubSubTypes.h @@ -0,0 +1,115 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PerformanceClassPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PERFORMANCECLASS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PERFORMANCECLASS_PUBSUBTYPES_H_ + +#include +#include + +#include "PerformanceClass.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated PerformanceClass is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace PerformanceClass_Constants + { + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type PerformanceClass defined by the user in the IDL file. + * @ingroup PERFORMANCECLASS + */ + class PerformanceClassPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef PerformanceClass type; + + eProsima_user_DllExport PerformanceClassPubSubType(); + + eProsima_user_DllExport virtual ~PerformanceClassPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) PerformanceClass(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PERFORMANCECLASS_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipse.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipse.cxx new file mode 100644 index 00000000000..f8b73c2531d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipse.cxx @@ -0,0 +1,286 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PosConfidenceEllipse.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "PosConfidenceEllipse.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::PosConfidenceEllipse::PosConfidenceEllipse() +{ + // m_semi_major_confidence com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@4c03a37 + + // m_semi_minor_confidence com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@4c03a37 + + // m_semi_major_orientation com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@2e140e59 + + +} + +etsi_its_cam_msgs::msg::PosConfidenceEllipse::~PosConfidenceEllipse() +{ + + +} + +etsi_its_cam_msgs::msg::PosConfidenceEllipse::PosConfidenceEllipse( + const PosConfidenceEllipse& x) +{ + m_semi_major_confidence = x.m_semi_major_confidence; + m_semi_minor_confidence = x.m_semi_minor_confidence; + m_semi_major_orientation = x.m_semi_major_orientation; +} + +etsi_its_cam_msgs::msg::PosConfidenceEllipse::PosConfidenceEllipse( + PosConfidenceEllipse&& x) +{ + m_semi_major_confidence = std::move(x.m_semi_major_confidence); + m_semi_minor_confidence = std::move(x.m_semi_minor_confidence); + m_semi_major_orientation = std::move(x.m_semi_major_orientation); +} + +etsi_its_cam_msgs::msg::PosConfidenceEllipse& etsi_its_cam_msgs::msg::PosConfidenceEllipse::operator =( + const PosConfidenceEllipse& x) +{ + + m_semi_major_confidence = x.m_semi_major_confidence; + m_semi_minor_confidence = x.m_semi_minor_confidence; + m_semi_major_orientation = x.m_semi_major_orientation; + + return *this; +} + +etsi_its_cam_msgs::msg::PosConfidenceEllipse& etsi_its_cam_msgs::msg::PosConfidenceEllipse::operator =( + PosConfidenceEllipse&& x) +{ + + m_semi_major_confidence = std::move(x.m_semi_major_confidence); + m_semi_minor_confidence = std::move(x.m_semi_minor_confidence); + m_semi_major_orientation = std::move(x.m_semi_major_orientation); + + return *this; +} + +bool etsi_its_cam_msgs::msg::PosConfidenceEllipse::operator ==( + const PosConfidenceEllipse& x) const +{ + + return (m_semi_major_confidence == x.m_semi_major_confidence && m_semi_minor_confidence == x.m_semi_minor_confidence && m_semi_major_orientation == x.m_semi_major_orientation); +} + +bool etsi_its_cam_msgs::msg::PosConfidenceEllipse::operator !=( + const PosConfidenceEllipse& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::PosConfidenceEllipse::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::SemiAxisLength::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::SemiAxisLength::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::HeadingValue::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::PosConfidenceEllipse::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::PosConfidenceEllipse& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::SemiAxisLength::getCdrSerializedSize(data.semi_major_confidence(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::SemiAxisLength::getCdrSerializedSize(data.semi_minor_confidence(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::HeadingValue::getCdrSerializedSize(data.semi_major_orientation(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::PosConfidenceEllipse::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_semi_major_confidence; + scdr << m_semi_minor_confidence; + scdr << m_semi_major_orientation; + +} + +void etsi_its_cam_msgs::msg::PosConfidenceEllipse::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_semi_major_confidence; + dcdr >> m_semi_minor_confidence; + dcdr >> m_semi_major_orientation; +} + +/*! + * @brief This function copies the value in member semi_major_confidence + * @param _semi_major_confidence New value to be copied in member semi_major_confidence + */ +void etsi_its_cam_msgs::msg::PosConfidenceEllipse::semi_major_confidence( + const etsi_its_cam_msgs::msg::SemiAxisLength& _semi_major_confidence) +{ + m_semi_major_confidence = _semi_major_confidence; +} + +/*! + * @brief This function moves the value in member semi_major_confidence + * @param _semi_major_confidence New value to be moved in member semi_major_confidence + */ +void etsi_its_cam_msgs::msg::PosConfidenceEllipse::semi_major_confidence( + etsi_its_cam_msgs::msg::SemiAxisLength&& _semi_major_confidence) +{ + m_semi_major_confidence = std::move(_semi_major_confidence); +} + +/*! + * @brief This function returns a constant reference to member semi_major_confidence + * @return Constant reference to member semi_major_confidence + */ +const etsi_its_cam_msgs::msg::SemiAxisLength& etsi_its_cam_msgs::msg::PosConfidenceEllipse::semi_major_confidence() const +{ + return m_semi_major_confidence; +} + +/*! + * @brief This function returns a reference to member semi_major_confidence + * @return Reference to member semi_major_confidence + */ +etsi_its_cam_msgs::msg::SemiAxisLength& etsi_its_cam_msgs::msg::PosConfidenceEllipse::semi_major_confidence() +{ + return m_semi_major_confidence; +} +/*! + * @brief This function copies the value in member semi_minor_confidence + * @param _semi_minor_confidence New value to be copied in member semi_minor_confidence + */ +void etsi_its_cam_msgs::msg::PosConfidenceEllipse::semi_minor_confidence( + const etsi_its_cam_msgs::msg::SemiAxisLength& _semi_minor_confidence) +{ + m_semi_minor_confidence = _semi_minor_confidence; +} + +/*! + * @brief This function moves the value in member semi_minor_confidence + * @param _semi_minor_confidence New value to be moved in member semi_minor_confidence + */ +void etsi_its_cam_msgs::msg::PosConfidenceEllipse::semi_minor_confidence( + etsi_its_cam_msgs::msg::SemiAxisLength&& _semi_minor_confidence) +{ + m_semi_minor_confidence = std::move(_semi_minor_confidence); +} + +/*! + * @brief This function returns a constant reference to member semi_minor_confidence + * @return Constant reference to member semi_minor_confidence + */ +const etsi_its_cam_msgs::msg::SemiAxisLength& etsi_its_cam_msgs::msg::PosConfidenceEllipse::semi_minor_confidence() const +{ + return m_semi_minor_confidence; +} + +/*! + * @brief This function returns a reference to member semi_minor_confidence + * @return Reference to member semi_minor_confidence + */ +etsi_its_cam_msgs::msg::SemiAxisLength& etsi_its_cam_msgs::msg::PosConfidenceEllipse::semi_minor_confidence() +{ + return m_semi_minor_confidence; +} +/*! + * @brief This function copies the value in member semi_major_orientation + * @param _semi_major_orientation New value to be copied in member semi_major_orientation + */ +void etsi_its_cam_msgs::msg::PosConfidenceEllipse::semi_major_orientation( + const etsi_its_cam_msgs::msg::HeadingValue& _semi_major_orientation) +{ + m_semi_major_orientation = _semi_major_orientation; +} + +/*! + * @brief This function moves the value in member semi_major_orientation + * @param _semi_major_orientation New value to be moved in member semi_major_orientation + */ +void etsi_its_cam_msgs::msg::PosConfidenceEllipse::semi_major_orientation( + etsi_its_cam_msgs::msg::HeadingValue&& _semi_major_orientation) +{ + m_semi_major_orientation = std::move(_semi_major_orientation); +} + +/*! + * @brief This function returns a constant reference to member semi_major_orientation + * @return Constant reference to member semi_major_orientation + */ +const etsi_its_cam_msgs::msg::HeadingValue& etsi_its_cam_msgs::msg::PosConfidenceEllipse::semi_major_orientation() const +{ + return m_semi_major_orientation; +} + +/*! + * @brief This function returns a reference to member semi_major_orientation + * @return Reference to member semi_major_orientation + */ +etsi_its_cam_msgs::msg::HeadingValue& etsi_its_cam_msgs::msg::PosConfidenceEllipse::semi_major_orientation() +{ + return m_semi_major_orientation; +} + +size_t etsi_its_cam_msgs::msg::PosConfidenceEllipse::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::PosConfidenceEllipse::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::PosConfidenceEllipse::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipse.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipse.h new file mode 100644 index 00000000000..95472b3428e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipse.h @@ -0,0 +1,270 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PosConfidenceEllipse.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_POSCONFIDENCEELLIPSE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_POSCONFIDENCEELLIPSE_H_ + +#include "HeadingValue.h" +#include "SemiAxisLength.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(PosConfidenceEllipse_SOURCE) +#define PosConfidenceEllipse_DllAPI __declspec( dllexport ) +#else +#define PosConfidenceEllipse_DllAPI __declspec( dllimport ) +#endif // PosConfidenceEllipse_SOURCE +#else +#define PosConfidenceEllipse_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define PosConfidenceEllipse_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure PosConfidenceEllipse defined by the user in the IDL file. + * @ingroup POSCONFIDENCEELLIPSE + */ + class PosConfidenceEllipse + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport PosConfidenceEllipse(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~PosConfidenceEllipse(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::PosConfidenceEllipse that will be copied. + */ + eProsima_user_DllExport PosConfidenceEllipse( + const PosConfidenceEllipse& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::PosConfidenceEllipse that will be copied. + */ + eProsima_user_DllExport PosConfidenceEllipse( + PosConfidenceEllipse&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::PosConfidenceEllipse that will be copied. + */ + eProsima_user_DllExport PosConfidenceEllipse& operator =( + const PosConfidenceEllipse& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::PosConfidenceEllipse that will be copied. + */ + eProsima_user_DllExport PosConfidenceEllipse& operator =( + PosConfidenceEllipse&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::PosConfidenceEllipse object to compare. + */ + eProsima_user_DllExport bool operator ==( + const PosConfidenceEllipse& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::PosConfidenceEllipse object to compare. + */ + eProsima_user_DllExport bool operator !=( + const PosConfidenceEllipse& x) const; + + /*! + * @brief This function copies the value in member semi_major_confidence + * @param _semi_major_confidence New value to be copied in member semi_major_confidence + */ + eProsima_user_DllExport void semi_major_confidence( + const etsi_its_cam_msgs::msg::SemiAxisLength& _semi_major_confidence); + + /*! + * @brief This function moves the value in member semi_major_confidence + * @param _semi_major_confidence New value to be moved in member semi_major_confidence + */ + eProsima_user_DllExport void semi_major_confidence( + etsi_its_cam_msgs::msg::SemiAxisLength&& _semi_major_confidence); + + /*! + * @brief This function returns a constant reference to member semi_major_confidence + * @return Constant reference to member semi_major_confidence + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::SemiAxisLength& semi_major_confidence() const; + + /*! + * @brief This function returns a reference to member semi_major_confidence + * @return Reference to member semi_major_confidence + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::SemiAxisLength& semi_major_confidence(); + /*! + * @brief This function copies the value in member semi_minor_confidence + * @param _semi_minor_confidence New value to be copied in member semi_minor_confidence + */ + eProsima_user_DllExport void semi_minor_confidence( + const etsi_its_cam_msgs::msg::SemiAxisLength& _semi_minor_confidence); + + /*! + * @brief This function moves the value in member semi_minor_confidence + * @param _semi_minor_confidence New value to be moved in member semi_minor_confidence + */ + eProsima_user_DllExport void semi_minor_confidence( + etsi_its_cam_msgs::msg::SemiAxisLength&& _semi_minor_confidence); + + /*! + * @brief This function returns a constant reference to member semi_minor_confidence + * @return Constant reference to member semi_minor_confidence + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::SemiAxisLength& semi_minor_confidence() const; + + /*! + * @brief This function returns a reference to member semi_minor_confidence + * @return Reference to member semi_minor_confidence + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::SemiAxisLength& semi_minor_confidence(); + /*! + * @brief This function copies the value in member semi_major_orientation + * @param _semi_major_orientation New value to be copied in member semi_major_orientation + */ + eProsima_user_DllExport void semi_major_orientation( + const etsi_its_cam_msgs::msg::HeadingValue& _semi_major_orientation); + + /*! + * @brief This function moves the value in member semi_major_orientation + * @param _semi_major_orientation New value to be moved in member semi_major_orientation + */ + eProsima_user_DllExport void semi_major_orientation( + etsi_its_cam_msgs::msg::HeadingValue&& _semi_major_orientation); + + /*! + * @brief This function returns a constant reference to member semi_major_orientation + * @return Constant reference to member semi_major_orientation + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::HeadingValue& semi_major_orientation() const; + + /*! + * @brief This function returns a reference to member semi_major_orientation + * @return Reference to member semi_major_orientation + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::HeadingValue& semi_major_orientation(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::PosConfidenceEllipse& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::SemiAxisLength m_semi_major_confidence; + etsi_its_cam_msgs::msg::SemiAxisLength m_semi_minor_confidence; + etsi_its_cam_msgs::msg::HeadingValue m_semi_major_orientation; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_POSCONFIDENCEELLIPSE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipsePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipsePubSubTypes.cxx new file mode 100644 index 00000000000..b27946f719d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipsePubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PosConfidenceEllipsePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "PosConfidenceEllipsePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + PosConfidenceEllipsePubSubType::PosConfidenceEllipsePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::PosConfidenceEllipse_"); + auto type_size = PosConfidenceEllipse::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = PosConfidenceEllipse::isKeyDefined(); + size_t keyLength = PosConfidenceEllipse::getKeyMaxCdrSerializedSize() > 16 ? + PosConfidenceEllipse::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + PosConfidenceEllipsePubSubType::~PosConfidenceEllipsePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool PosConfidenceEllipsePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + PosConfidenceEllipse* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool PosConfidenceEllipsePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + PosConfidenceEllipse* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function PosConfidenceEllipsePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* PosConfidenceEllipsePubSubType::createData() + { + return reinterpret_cast(new PosConfidenceEllipse()); + } + + void PosConfidenceEllipsePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool PosConfidenceEllipsePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + PosConfidenceEllipse* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + PosConfidenceEllipse::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || PosConfidenceEllipse::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipsePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipsePubSubTypes.h new file mode 100644 index 00000000000..9535c127377 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipsePubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PosConfidenceEllipsePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_POSCONFIDENCEELLIPSE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_POSCONFIDENCEELLIPSE_PUBSUBTYPES_H_ + +#include +#include + +#include "PosConfidenceEllipse.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated PosConfidenceEllipse is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type PosConfidenceEllipse defined by the user in the IDL file. + * @ingroup POSCONFIDENCEELLIPSE + */ + class PosConfidenceEllipsePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef PosConfidenceEllipse type; + + eProsima_user_DllExport PosConfidenceEllipsePubSubType(); + + eProsima_user_DllExport virtual ~PosConfidenceEllipsePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) PosConfidenceEllipse(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_POSCONFIDENCEELLIPSE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.cxx new file mode 100644 index 00000000000..77723869509 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.cxx @@ -0,0 +1,559 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ProtectedCommunicationZone.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "ProtectedCommunicationZone.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::ProtectedCommunicationZone::ProtectedCommunicationZone() +{ + // m_protected_zone_type com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@545f80bf + + // m_expiry_time com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@66f66866 + + // m_expiry_time_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@22fa55b2 + m_expiry_time_is_present = false; + // m_protected_zone_latitude com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@4d666b41 + + // m_protected_zone_longitude com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@6594402a + + // m_protected_zone_radius com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@30f4b1a6 + + // m_protected_zone_radius_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@405325cf + m_protected_zone_radius_is_present = false; + // m_protected_zone_id com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@3e1162e7 + + // m_protected_zone_id_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@79c3f01f + m_protected_zone_id_is_present = false; + +} + +etsi_its_cam_msgs::msg::ProtectedCommunicationZone::~ProtectedCommunicationZone() +{ + + + + + + + + +} + +etsi_its_cam_msgs::msg::ProtectedCommunicationZone::ProtectedCommunicationZone( + const ProtectedCommunicationZone& x) +{ + m_protected_zone_type = x.m_protected_zone_type; + m_expiry_time = x.m_expiry_time; + m_expiry_time_is_present = x.m_expiry_time_is_present; + m_protected_zone_latitude = x.m_protected_zone_latitude; + m_protected_zone_longitude = x.m_protected_zone_longitude; + m_protected_zone_radius = x.m_protected_zone_radius; + m_protected_zone_radius_is_present = x.m_protected_zone_radius_is_present; + m_protected_zone_id = x.m_protected_zone_id; + m_protected_zone_id_is_present = x.m_protected_zone_id_is_present; +} + +etsi_its_cam_msgs::msg::ProtectedCommunicationZone::ProtectedCommunicationZone( + ProtectedCommunicationZone&& x) +{ + m_protected_zone_type = std::move(x.m_protected_zone_type); + m_expiry_time = std::move(x.m_expiry_time); + m_expiry_time_is_present = x.m_expiry_time_is_present; + m_protected_zone_latitude = std::move(x.m_protected_zone_latitude); + m_protected_zone_longitude = std::move(x.m_protected_zone_longitude); + m_protected_zone_radius = std::move(x.m_protected_zone_radius); + m_protected_zone_radius_is_present = x.m_protected_zone_radius_is_present; + m_protected_zone_id = std::move(x.m_protected_zone_id); + m_protected_zone_id_is_present = x.m_protected_zone_id_is_present; +} + +etsi_its_cam_msgs::msg::ProtectedCommunicationZone& etsi_its_cam_msgs::msg::ProtectedCommunicationZone::operator =( + const ProtectedCommunicationZone& x) +{ + + m_protected_zone_type = x.m_protected_zone_type; + m_expiry_time = x.m_expiry_time; + m_expiry_time_is_present = x.m_expiry_time_is_present; + m_protected_zone_latitude = x.m_protected_zone_latitude; + m_protected_zone_longitude = x.m_protected_zone_longitude; + m_protected_zone_radius = x.m_protected_zone_radius; + m_protected_zone_radius_is_present = x.m_protected_zone_radius_is_present; + m_protected_zone_id = x.m_protected_zone_id; + m_protected_zone_id_is_present = x.m_protected_zone_id_is_present; + + return *this; +} + +etsi_its_cam_msgs::msg::ProtectedCommunicationZone& etsi_its_cam_msgs::msg::ProtectedCommunicationZone::operator =( + ProtectedCommunicationZone&& x) +{ + + m_protected_zone_type = std::move(x.m_protected_zone_type); + m_expiry_time = std::move(x.m_expiry_time); + m_expiry_time_is_present = x.m_expiry_time_is_present; + m_protected_zone_latitude = std::move(x.m_protected_zone_latitude); + m_protected_zone_longitude = std::move(x.m_protected_zone_longitude); + m_protected_zone_radius = std::move(x.m_protected_zone_radius); + m_protected_zone_radius_is_present = x.m_protected_zone_radius_is_present; + m_protected_zone_id = std::move(x.m_protected_zone_id); + m_protected_zone_id_is_present = x.m_protected_zone_id_is_present; + + return *this; +} + +bool etsi_its_cam_msgs::msg::ProtectedCommunicationZone::operator ==( + const ProtectedCommunicationZone& x) const +{ + + return (m_protected_zone_type == x.m_protected_zone_type && m_expiry_time == x.m_expiry_time && m_expiry_time_is_present == x.m_expiry_time_is_present && m_protected_zone_latitude == x.m_protected_zone_latitude && m_protected_zone_longitude == x.m_protected_zone_longitude && m_protected_zone_radius == x.m_protected_zone_radius && m_protected_zone_radius_is_present == x.m_protected_zone_radius_is_present && m_protected_zone_id == x.m_protected_zone_id && m_protected_zone_id_is_present == x.m_protected_zone_id_is_present); +} + +bool etsi_its_cam_msgs::msg::ProtectedCommunicationZone::operator !=( + const ProtectedCommunicationZone& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::ProtectedCommunicationZone::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::ProtectedZoneType::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::TimestampIts::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::Latitude::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::Longitude::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::ProtectedZoneRadius::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::ProtectedZoneID::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::ProtectedCommunicationZone::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::ProtectedCommunicationZone& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::ProtectedZoneType::getCdrSerializedSize(data.protected_zone_type(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::TimestampIts::getCdrSerializedSize(data.expiry_time(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::Latitude::getCdrSerializedSize(data.protected_zone_latitude(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::Longitude::getCdrSerializedSize(data.protected_zone_longitude(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::ProtectedZoneRadius::getCdrSerializedSize(data.protected_zone_radius(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::ProtectedZoneID::getCdrSerializedSize(data.protected_zone_id(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::ProtectedCommunicationZone::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_protected_zone_type; + scdr << m_expiry_time; + scdr << m_expiry_time_is_present; + scdr << m_protected_zone_latitude; + scdr << m_protected_zone_longitude; + scdr << m_protected_zone_radius; + scdr << m_protected_zone_radius_is_present; + scdr << m_protected_zone_id; + scdr << m_protected_zone_id_is_present; + +} + +void etsi_its_cam_msgs::msg::ProtectedCommunicationZone::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_protected_zone_type; + dcdr >> m_expiry_time; + dcdr >> m_expiry_time_is_present; + dcdr >> m_protected_zone_latitude; + dcdr >> m_protected_zone_longitude; + dcdr >> m_protected_zone_radius; + dcdr >> m_protected_zone_radius_is_present; + dcdr >> m_protected_zone_id; + dcdr >> m_protected_zone_id_is_present; +} + +/*! + * @brief This function copies the value in member protected_zone_type + * @param _protected_zone_type New value to be copied in member protected_zone_type + */ +void etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_type( + const etsi_its_cam_msgs::msg::ProtectedZoneType& _protected_zone_type) +{ + m_protected_zone_type = _protected_zone_type; +} + +/*! + * @brief This function moves the value in member protected_zone_type + * @param _protected_zone_type New value to be moved in member protected_zone_type + */ +void etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_type( + etsi_its_cam_msgs::msg::ProtectedZoneType&& _protected_zone_type) +{ + m_protected_zone_type = std::move(_protected_zone_type); +} + +/*! + * @brief This function returns a constant reference to member protected_zone_type + * @return Constant reference to member protected_zone_type + */ +const etsi_its_cam_msgs::msg::ProtectedZoneType& etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_type() const +{ + return m_protected_zone_type; +} + +/*! + * @brief This function returns a reference to member protected_zone_type + * @return Reference to member protected_zone_type + */ +etsi_its_cam_msgs::msg::ProtectedZoneType& etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_type() +{ + return m_protected_zone_type; +} +/*! + * @brief This function copies the value in member expiry_time + * @param _expiry_time New value to be copied in member expiry_time + */ +void etsi_its_cam_msgs::msg::ProtectedCommunicationZone::expiry_time( + const etsi_its_cam_msgs::msg::TimestampIts& _expiry_time) +{ + m_expiry_time = _expiry_time; +} + +/*! + * @brief This function moves the value in member expiry_time + * @param _expiry_time New value to be moved in member expiry_time + */ +void etsi_its_cam_msgs::msg::ProtectedCommunicationZone::expiry_time( + etsi_its_cam_msgs::msg::TimestampIts&& _expiry_time) +{ + m_expiry_time = std::move(_expiry_time); +} + +/*! + * @brief This function returns a constant reference to member expiry_time + * @return Constant reference to member expiry_time + */ +const etsi_its_cam_msgs::msg::TimestampIts& etsi_its_cam_msgs::msg::ProtectedCommunicationZone::expiry_time() const +{ + return m_expiry_time; +} + +/*! + * @brief This function returns a reference to member expiry_time + * @return Reference to member expiry_time + */ +etsi_its_cam_msgs::msg::TimestampIts& etsi_its_cam_msgs::msg::ProtectedCommunicationZone::expiry_time() +{ + return m_expiry_time; +} +/*! + * @brief This function sets a value in member expiry_time_is_present + * @param _expiry_time_is_present New value for member expiry_time_is_present + */ +void etsi_its_cam_msgs::msg::ProtectedCommunicationZone::expiry_time_is_present( + bool _expiry_time_is_present) +{ + m_expiry_time_is_present = _expiry_time_is_present; +} + +/*! + * @brief This function returns the value of member expiry_time_is_present + * @return Value of member expiry_time_is_present + */ +bool etsi_its_cam_msgs::msg::ProtectedCommunicationZone::expiry_time_is_present() const +{ + return m_expiry_time_is_present; +} + +/*! + * @brief This function returns a reference to member expiry_time_is_present + * @return Reference to member expiry_time_is_present + */ +bool& etsi_its_cam_msgs::msg::ProtectedCommunicationZone::expiry_time_is_present() +{ + return m_expiry_time_is_present; +} + +/*! + * @brief This function copies the value in member protected_zone_latitude + * @param _protected_zone_latitude New value to be copied in member protected_zone_latitude + */ +void etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_latitude( + const etsi_its_cam_msgs::msg::Latitude& _protected_zone_latitude) +{ + m_protected_zone_latitude = _protected_zone_latitude; +} + +/*! + * @brief This function moves the value in member protected_zone_latitude + * @param _protected_zone_latitude New value to be moved in member protected_zone_latitude + */ +void etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_latitude( + etsi_its_cam_msgs::msg::Latitude&& _protected_zone_latitude) +{ + m_protected_zone_latitude = std::move(_protected_zone_latitude); +} + +/*! + * @brief This function returns a constant reference to member protected_zone_latitude + * @return Constant reference to member protected_zone_latitude + */ +const etsi_its_cam_msgs::msg::Latitude& etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_latitude() const +{ + return m_protected_zone_latitude; +} + +/*! + * @brief This function returns a reference to member protected_zone_latitude + * @return Reference to member protected_zone_latitude + */ +etsi_its_cam_msgs::msg::Latitude& etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_latitude() +{ + return m_protected_zone_latitude; +} +/*! + * @brief This function copies the value in member protected_zone_longitude + * @param _protected_zone_longitude New value to be copied in member protected_zone_longitude + */ +void etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_longitude( + const etsi_its_cam_msgs::msg::Longitude& _protected_zone_longitude) +{ + m_protected_zone_longitude = _protected_zone_longitude; +} + +/*! + * @brief This function moves the value in member protected_zone_longitude + * @param _protected_zone_longitude New value to be moved in member protected_zone_longitude + */ +void etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_longitude( + etsi_its_cam_msgs::msg::Longitude&& _protected_zone_longitude) +{ + m_protected_zone_longitude = std::move(_protected_zone_longitude); +} + +/*! + * @brief This function returns a constant reference to member protected_zone_longitude + * @return Constant reference to member protected_zone_longitude + */ +const etsi_its_cam_msgs::msg::Longitude& etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_longitude() const +{ + return m_protected_zone_longitude; +} + +/*! + * @brief This function returns a reference to member protected_zone_longitude + * @return Reference to member protected_zone_longitude + */ +etsi_its_cam_msgs::msg::Longitude& etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_longitude() +{ + return m_protected_zone_longitude; +} +/*! + * @brief This function copies the value in member protected_zone_radius + * @param _protected_zone_radius New value to be copied in member protected_zone_radius + */ +void etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_radius( + const etsi_its_cam_msgs::msg::ProtectedZoneRadius& _protected_zone_radius) +{ + m_protected_zone_radius = _protected_zone_radius; +} + +/*! + * @brief This function moves the value in member protected_zone_radius + * @param _protected_zone_radius New value to be moved in member protected_zone_radius + */ +void etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_radius( + etsi_its_cam_msgs::msg::ProtectedZoneRadius&& _protected_zone_radius) +{ + m_protected_zone_radius = std::move(_protected_zone_radius); +} + +/*! + * @brief This function returns a constant reference to member protected_zone_radius + * @return Constant reference to member protected_zone_radius + */ +const etsi_its_cam_msgs::msg::ProtectedZoneRadius& etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_radius() const +{ + return m_protected_zone_radius; +} + +/*! + * @brief This function returns a reference to member protected_zone_radius + * @return Reference to member protected_zone_radius + */ +etsi_its_cam_msgs::msg::ProtectedZoneRadius& etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_radius() +{ + return m_protected_zone_radius; +} +/*! + * @brief This function sets a value in member protected_zone_radius_is_present + * @param _protected_zone_radius_is_present New value for member protected_zone_radius_is_present + */ +void etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_radius_is_present( + bool _protected_zone_radius_is_present) +{ + m_protected_zone_radius_is_present = _protected_zone_radius_is_present; +} + +/*! + * @brief This function returns the value of member protected_zone_radius_is_present + * @return Value of member protected_zone_radius_is_present + */ +bool etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_radius_is_present() const +{ + return m_protected_zone_radius_is_present; +} + +/*! + * @brief This function returns a reference to member protected_zone_radius_is_present + * @return Reference to member protected_zone_radius_is_present + */ +bool& etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_radius_is_present() +{ + return m_protected_zone_radius_is_present; +} + +/*! + * @brief This function copies the value in member protected_zone_id + * @param _protected_zone_id New value to be copied in member protected_zone_id + */ +void etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_id( + const etsi_its_cam_msgs::msg::ProtectedZoneID& _protected_zone_id) +{ + m_protected_zone_id = _protected_zone_id; +} + +/*! + * @brief This function moves the value in member protected_zone_id + * @param _protected_zone_id New value to be moved in member protected_zone_id + */ +void etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_id( + etsi_its_cam_msgs::msg::ProtectedZoneID&& _protected_zone_id) +{ + m_protected_zone_id = std::move(_protected_zone_id); +} + +/*! + * @brief This function returns a constant reference to member protected_zone_id + * @return Constant reference to member protected_zone_id + */ +const etsi_its_cam_msgs::msg::ProtectedZoneID& etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_id() const +{ + return m_protected_zone_id; +} + +/*! + * @brief This function returns a reference to member protected_zone_id + * @return Reference to member protected_zone_id + */ +etsi_its_cam_msgs::msg::ProtectedZoneID& etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_id() +{ + return m_protected_zone_id; +} +/*! + * @brief This function sets a value in member protected_zone_id_is_present + * @param _protected_zone_id_is_present New value for member protected_zone_id_is_present + */ +void etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_id_is_present( + bool _protected_zone_id_is_present) +{ + m_protected_zone_id_is_present = _protected_zone_id_is_present; +} + +/*! + * @brief This function returns the value of member protected_zone_id_is_present + * @return Value of member protected_zone_id_is_present + */ +bool etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_id_is_present() const +{ + return m_protected_zone_id_is_present; +} + +/*! + * @brief This function returns a reference to member protected_zone_id_is_present + * @return Reference to member protected_zone_id_is_present + */ +bool& etsi_its_cam_msgs::msg::ProtectedCommunicationZone::protected_zone_id_is_present() +{ + return m_protected_zone_id_is_present; +} + + +size_t etsi_its_cam_msgs::msg::ProtectedCommunicationZone::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::ProtectedCommunicationZone::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::ProtectedCommunicationZone::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.h new file mode 100644 index 00000000000..c754f63c34c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.h @@ -0,0 +1,412 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ProtectedCommunicationZone.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONE_H_ + +#include "ProtectedZoneRadius.h" +#include "TimestampIts.h" +#include "ProtectedZoneID.h" +#include "ProtectedZoneType.h" +#include "Latitude.h" +#include "Longitude.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(ProtectedCommunicationZone_SOURCE) +#define ProtectedCommunicationZone_DllAPI __declspec( dllexport ) +#else +#define ProtectedCommunicationZone_DllAPI __declspec( dllimport ) +#endif // ProtectedCommunicationZone_SOURCE +#else +#define ProtectedCommunicationZone_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define ProtectedCommunicationZone_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure ProtectedCommunicationZone defined by the user in the IDL file. + * @ingroup PROTECTEDCOMMUNICATIONZONE + */ + class ProtectedCommunicationZone + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport ProtectedCommunicationZone(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~ProtectedCommunicationZone(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::ProtectedCommunicationZone that will be copied. + */ + eProsima_user_DllExport ProtectedCommunicationZone( + const ProtectedCommunicationZone& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::ProtectedCommunicationZone that will be copied. + */ + eProsima_user_DllExport ProtectedCommunicationZone( + ProtectedCommunicationZone&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::ProtectedCommunicationZone that will be copied. + */ + eProsima_user_DllExport ProtectedCommunicationZone& operator =( + const ProtectedCommunicationZone& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::ProtectedCommunicationZone that will be copied. + */ + eProsima_user_DllExport ProtectedCommunicationZone& operator =( + ProtectedCommunicationZone&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::ProtectedCommunicationZone object to compare. + */ + eProsima_user_DllExport bool operator ==( + const ProtectedCommunicationZone& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::ProtectedCommunicationZone object to compare. + */ + eProsima_user_DllExport bool operator !=( + const ProtectedCommunicationZone& x) const; + + /*! + * @brief This function copies the value in member protected_zone_type + * @param _protected_zone_type New value to be copied in member protected_zone_type + */ + eProsima_user_DllExport void protected_zone_type( + const etsi_its_cam_msgs::msg::ProtectedZoneType& _protected_zone_type); + + /*! + * @brief This function moves the value in member protected_zone_type + * @param _protected_zone_type New value to be moved in member protected_zone_type + */ + eProsima_user_DllExport void protected_zone_type( + etsi_its_cam_msgs::msg::ProtectedZoneType&& _protected_zone_type); + + /*! + * @brief This function returns a constant reference to member protected_zone_type + * @return Constant reference to member protected_zone_type + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::ProtectedZoneType& protected_zone_type() const; + + /*! + * @brief This function returns a reference to member protected_zone_type + * @return Reference to member protected_zone_type + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::ProtectedZoneType& protected_zone_type(); + /*! + * @brief This function copies the value in member expiry_time + * @param _expiry_time New value to be copied in member expiry_time + */ + eProsima_user_DllExport void expiry_time( + const etsi_its_cam_msgs::msg::TimestampIts& _expiry_time); + + /*! + * @brief This function moves the value in member expiry_time + * @param _expiry_time New value to be moved in member expiry_time + */ + eProsima_user_DllExport void expiry_time( + etsi_its_cam_msgs::msg::TimestampIts&& _expiry_time); + + /*! + * @brief This function returns a constant reference to member expiry_time + * @return Constant reference to member expiry_time + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::TimestampIts& expiry_time() const; + + /*! + * @brief This function returns a reference to member expiry_time + * @return Reference to member expiry_time + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::TimestampIts& expiry_time(); + /*! + * @brief This function sets a value in member expiry_time_is_present + * @param _expiry_time_is_present New value for member expiry_time_is_present + */ + eProsima_user_DllExport void expiry_time_is_present( + bool _expiry_time_is_present); + + /*! + * @brief This function returns the value of member expiry_time_is_present + * @return Value of member expiry_time_is_present + */ + eProsima_user_DllExport bool expiry_time_is_present() const; + + /*! + * @brief This function returns a reference to member expiry_time_is_present + * @return Reference to member expiry_time_is_present + */ + eProsima_user_DllExport bool& expiry_time_is_present(); + + /*! + * @brief This function copies the value in member protected_zone_latitude + * @param _protected_zone_latitude New value to be copied in member protected_zone_latitude + */ + eProsima_user_DllExport void protected_zone_latitude( + const etsi_its_cam_msgs::msg::Latitude& _protected_zone_latitude); + + /*! + * @brief This function moves the value in member protected_zone_latitude + * @param _protected_zone_latitude New value to be moved in member protected_zone_latitude + */ + eProsima_user_DllExport void protected_zone_latitude( + etsi_its_cam_msgs::msg::Latitude&& _protected_zone_latitude); + + /*! + * @brief This function returns a constant reference to member protected_zone_latitude + * @return Constant reference to member protected_zone_latitude + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::Latitude& protected_zone_latitude() const; + + /*! + * @brief This function returns a reference to member protected_zone_latitude + * @return Reference to member protected_zone_latitude + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::Latitude& protected_zone_latitude(); + /*! + * @brief This function copies the value in member protected_zone_longitude + * @param _protected_zone_longitude New value to be copied in member protected_zone_longitude + */ + eProsima_user_DllExport void protected_zone_longitude( + const etsi_its_cam_msgs::msg::Longitude& _protected_zone_longitude); + + /*! + * @brief This function moves the value in member protected_zone_longitude + * @param _protected_zone_longitude New value to be moved in member protected_zone_longitude + */ + eProsima_user_DllExport void protected_zone_longitude( + etsi_its_cam_msgs::msg::Longitude&& _protected_zone_longitude); + + /*! + * @brief This function returns a constant reference to member protected_zone_longitude + * @return Constant reference to member protected_zone_longitude + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::Longitude& protected_zone_longitude() const; + + /*! + * @brief This function returns a reference to member protected_zone_longitude + * @return Reference to member protected_zone_longitude + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::Longitude& protected_zone_longitude(); + /*! + * @brief This function copies the value in member protected_zone_radius + * @param _protected_zone_radius New value to be copied in member protected_zone_radius + */ + eProsima_user_DllExport void protected_zone_radius( + const etsi_its_cam_msgs::msg::ProtectedZoneRadius& _protected_zone_radius); + + /*! + * @brief This function moves the value in member protected_zone_radius + * @param _protected_zone_radius New value to be moved in member protected_zone_radius + */ + eProsima_user_DllExport void protected_zone_radius( + etsi_its_cam_msgs::msg::ProtectedZoneRadius&& _protected_zone_radius); + + /*! + * @brief This function returns a constant reference to member protected_zone_radius + * @return Constant reference to member protected_zone_radius + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::ProtectedZoneRadius& protected_zone_radius() const; + + /*! + * @brief This function returns a reference to member protected_zone_radius + * @return Reference to member protected_zone_radius + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::ProtectedZoneRadius& protected_zone_radius(); + /*! + * @brief This function sets a value in member protected_zone_radius_is_present + * @param _protected_zone_radius_is_present New value for member protected_zone_radius_is_present + */ + eProsima_user_DllExport void protected_zone_radius_is_present( + bool _protected_zone_radius_is_present); + + /*! + * @brief This function returns the value of member protected_zone_radius_is_present + * @return Value of member protected_zone_radius_is_present + */ + eProsima_user_DllExport bool protected_zone_radius_is_present() const; + + /*! + * @brief This function returns a reference to member protected_zone_radius_is_present + * @return Reference to member protected_zone_radius_is_present + */ + eProsima_user_DllExport bool& protected_zone_radius_is_present(); + + /*! + * @brief This function copies the value in member protected_zone_id + * @param _protected_zone_id New value to be copied in member protected_zone_id + */ + eProsima_user_DllExport void protected_zone_id( + const etsi_its_cam_msgs::msg::ProtectedZoneID& _protected_zone_id); + + /*! + * @brief This function moves the value in member protected_zone_id + * @param _protected_zone_id New value to be moved in member protected_zone_id + */ + eProsima_user_DllExport void protected_zone_id( + etsi_its_cam_msgs::msg::ProtectedZoneID&& _protected_zone_id); + + /*! + * @brief This function returns a constant reference to member protected_zone_id + * @return Constant reference to member protected_zone_id + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::ProtectedZoneID& protected_zone_id() const; + + /*! + * @brief This function returns a reference to member protected_zone_id + * @return Reference to member protected_zone_id + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::ProtectedZoneID& protected_zone_id(); + /*! + * @brief This function sets a value in member protected_zone_id_is_present + * @param _protected_zone_id_is_present New value for member protected_zone_id_is_present + */ + eProsima_user_DllExport void protected_zone_id_is_present( + bool _protected_zone_id_is_present); + + /*! + * @brief This function returns the value of member protected_zone_id_is_present + * @return Value of member protected_zone_id_is_present + */ + eProsima_user_DllExport bool protected_zone_id_is_present() const; + + /*! + * @brief This function returns a reference to member protected_zone_id_is_present + * @return Reference to member protected_zone_id_is_present + */ + eProsima_user_DllExport bool& protected_zone_id_is_present(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::ProtectedCommunicationZone& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::ProtectedZoneType m_protected_zone_type; + etsi_its_cam_msgs::msg::TimestampIts m_expiry_time; + bool m_expiry_time_is_present; + etsi_its_cam_msgs::msg::Latitude m_protected_zone_latitude; + etsi_its_cam_msgs::msg::Longitude m_protected_zone_longitude; + etsi_its_cam_msgs::msg::ProtectedZoneRadius m_protected_zone_radius; + bool m_protected_zone_radius_is_present; + etsi_its_cam_msgs::msg::ProtectedZoneID m_protected_zone_id; + bool m_protected_zone_id_is_present; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonePubSubTypes.cxx new file mode 100644 index 00000000000..0d433e12249 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonePubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ProtectedCommunicationZonePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "ProtectedCommunicationZonePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + ProtectedCommunicationZonePubSubType::ProtectedCommunicationZonePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::ProtectedCommunicationZone_"); + auto type_size = ProtectedCommunicationZone::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = ProtectedCommunicationZone::isKeyDefined(); + size_t keyLength = ProtectedCommunicationZone::getKeyMaxCdrSerializedSize() > 16 ? + ProtectedCommunicationZone::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + ProtectedCommunicationZonePubSubType::~ProtectedCommunicationZonePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool ProtectedCommunicationZonePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + ProtectedCommunicationZone* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool ProtectedCommunicationZonePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + ProtectedCommunicationZone* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function ProtectedCommunicationZonePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* ProtectedCommunicationZonePubSubType::createData() + { + return reinterpret_cast(new ProtectedCommunicationZone()); + } + + void ProtectedCommunicationZonePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool ProtectedCommunicationZonePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + ProtectedCommunicationZone* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + ProtectedCommunicationZone::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || ProtectedCommunicationZone::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonePubSubTypes.h new file mode 100644 index 00000000000..a4ec6e75efe --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonePubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ProtectedCommunicationZonePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONE_PUBSUBTYPES_H_ + +#include +#include + +#include "ProtectedCommunicationZone.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated ProtectedCommunicationZone is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type ProtectedCommunicationZone defined by the user in the IDL file. + * @ingroup PROTECTEDCOMMUNICATIONZONE + */ + class ProtectedCommunicationZonePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef ProtectedCommunicationZone type; + + eProsima_user_DllExport ProtectedCommunicationZonePubSubType(); + + eProsima_user_DllExport virtual ~ProtectedCommunicationZonePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) ProtectedCommunicationZone(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.cxx new file mode 100644 index 00000000000..acb8c9fbd09 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.cxx @@ -0,0 +1,201 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ProtectedCommunicationZonesRSU.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "ProtectedCommunicationZonesRSU.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + +etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::ProtectedCommunicationZonesRSU() +{ + // m_array com.eprosima.idl.parser.typecode.SequenceTypeCode@515f4131 + + +} + +etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::~ProtectedCommunicationZonesRSU() +{ +} + +etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::ProtectedCommunicationZonesRSU( + const ProtectedCommunicationZonesRSU& x) +{ + m_array = x.m_array; +} + +etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::ProtectedCommunicationZonesRSU( + ProtectedCommunicationZonesRSU&& x) +{ + m_array = std::move(x.m_array); +} + +etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU& etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::operator =( + const ProtectedCommunicationZonesRSU& x) +{ + + m_array = x.m_array; + + return *this; +} + +etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU& etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::operator =( + ProtectedCommunicationZonesRSU&& x) +{ + + m_array = std::move(x.m_array); + + return *this; +} + +bool etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::operator ==( + const ProtectedCommunicationZonesRSU& x) const +{ + + return (m_array == x.m_array); +} + +bool etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::operator !=( + const ProtectedCommunicationZonesRSU& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < 100; ++a) + { + current_alignment += etsi_its_cam_msgs::msg::ProtectedCommunicationZone::getMaxCdrSerializedSize(current_alignment);} + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < data.array().size(); ++a) + { + current_alignment += etsi_its_cam_msgs::msg::ProtectedCommunicationZone::getCdrSerializedSize(data.array().at(a), current_alignment);} + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_array; +} + +void etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_array;} + +/*! + * @brief This function copies the value in member array + * @param _array New value to be copied in member array + */ +void etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::array( + const std::vector& _array) +{ + m_array = _array; +} + +/*! + * @brief This function moves the value in member array + * @param _array New value to be moved in member array + */ +void etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::array( + std::vector&& _array) +{ + m_array = std::move(_array); +} + +/*! + * @brief This function returns a constant reference to member array + * @return Constant reference to member array + */ +const std::vector& etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::array() const +{ + return m_array; +} + +/*! + * @brief This function returns a reference to member array + * @return Reference to member array + */ +std::vector& etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::array() +{ + return m_array; +} + +size_t etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.h new file mode 100644 index 00000000000..b9fff22407d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.h @@ -0,0 +1,221 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ProtectedCommunicationZonesRSU.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONESRSU_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONESRSU_H_ + +#include "ProtectedCommunicationZone.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(ProtectedCommunicationZonesRSU_SOURCE) +#define ProtectedCommunicationZonesRSU_DllAPI __declspec( dllexport ) +#else +#define ProtectedCommunicationZonesRSU_DllAPI __declspec( dllimport ) +#endif // ProtectedCommunicationZonesRSU_SOURCE +#else +#define ProtectedCommunicationZonesRSU_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define ProtectedCommunicationZonesRSU_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace ProtectedCommunicationZonesRSU_Constants { + const uint8_t MIN_SIZE = 1; + const uint8_t MAX_SIZE = 16; + } // namespace ProtectedCommunicationZonesRSU_Constants + /*! + * @brief This class represents the structure ProtectedCommunicationZonesRSU defined by the user in the IDL file. + * @ingroup PROTECTEDCOMMUNICATIONZONESRSU + */ + class ProtectedCommunicationZonesRSU + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport ProtectedCommunicationZonesRSU(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~ProtectedCommunicationZonesRSU(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU that will be copied. + */ + eProsima_user_DllExport ProtectedCommunicationZonesRSU( + const ProtectedCommunicationZonesRSU& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU that will be copied. + */ + eProsima_user_DllExport ProtectedCommunicationZonesRSU( + ProtectedCommunicationZonesRSU&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU that will be copied. + */ + eProsima_user_DllExport ProtectedCommunicationZonesRSU& operator =( + const ProtectedCommunicationZonesRSU& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU that will be copied. + */ + eProsima_user_DllExport ProtectedCommunicationZonesRSU& operator =( + ProtectedCommunicationZonesRSU&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU object to compare. + */ + eProsima_user_DllExport bool operator ==( + const ProtectedCommunicationZonesRSU& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU object to compare. + */ + eProsima_user_DllExport bool operator !=( + const ProtectedCommunicationZonesRSU& x) const; + + /*! + * @brief This function copies the value in member array + * @param _array New value to be copied in member array + */ + eProsima_user_DllExport void array( + const std::vector& _array); + + /*! + * @brief This function moves the value in member array + * @param _array New value to be moved in member array + */ + eProsima_user_DllExport void array( + std::vector&& _array); + + /*! + * @brief This function returns a constant reference to member array + * @return Constant reference to member array + */ + eProsima_user_DllExport const std::vector& array() const; + + /*! + * @brief This function returns a reference to member array + * @return Reference to member array + */ + eProsima_user_DllExport std::vector& array(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std::vector m_array; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONESRSU_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSUPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSUPubSubTypes.cxx new file mode 100644 index 00000000000..8c8bf7587b2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSUPubSubTypes.cxx @@ -0,0 +1,181 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ProtectedCommunicationZonesRSUPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "ProtectedCommunicationZonesRSUPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace ProtectedCommunicationZonesRSU_Constants { + + + + } //End of namespace ProtectedCommunicationZonesRSU_Constants + ProtectedCommunicationZonesRSUPubSubType::ProtectedCommunicationZonesRSUPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::ProtectedCommunicationZonesRSU_"); + auto type_size = ProtectedCommunicationZonesRSU::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = ProtectedCommunicationZonesRSU::isKeyDefined(); + size_t keyLength = ProtectedCommunicationZonesRSU::getKeyMaxCdrSerializedSize() > 16 ? + ProtectedCommunicationZonesRSU::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + ProtectedCommunicationZonesRSUPubSubType::~ProtectedCommunicationZonesRSUPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool ProtectedCommunicationZonesRSUPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + ProtectedCommunicationZonesRSU* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool ProtectedCommunicationZonesRSUPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + ProtectedCommunicationZonesRSU* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function ProtectedCommunicationZonesRSUPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* ProtectedCommunicationZonesRSUPubSubType::createData() + { + return reinterpret_cast(new ProtectedCommunicationZonesRSU()); + } + + void ProtectedCommunicationZonesRSUPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool ProtectedCommunicationZonesRSUPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + ProtectedCommunicationZonesRSU* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + ProtectedCommunicationZonesRSU::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || ProtectedCommunicationZonesRSU::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSUPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSUPubSubTypes.h new file mode 100644 index 00000000000..bb68647494c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSUPubSubTypes.h @@ -0,0 +1,112 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ProtectedCommunicationZonesRSUPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONESRSU_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONESRSU_PUBSUBTYPES_H_ + +#include +#include + +#include "ProtectedCommunicationZonesRSU.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated ProtectedCommunicationZonesRSU is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace ProtectedCommunicationZonesRSU_Constants + { + + + } + /*! + * @brief This class represents the TopicDataType of the type ProtectedCommunicationZonesRSU defined by the user in the IDL file. + * @ingroup PROTECTEDCOMMUNICATIONZONESRSU + */ + class ProtectedCommunicationZonesRSUPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef ProtectedCommunicationZonesRSU type; + + eProsima_user_DllExport ProtectedCommunicationZonesRSUPubSubType(); + + eProsima_user_DllExport virtual ~ProtectedCommunicationZonesRSUPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONESRSU_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneID.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneID.cxx new file mode 100644 index 00000000000..6c4ab3e2dd9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneID.cxx @@ -0,0 +1,186 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ProtectedZoneID.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "ProtectedZoneID.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + +etsi_its_cam_msgs::msg::ProtectedZoneID::ProtectedZoneID() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@27fde870 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::ProtectedZoneID::~ProtectedZoneID() +{ +} + +etsi_its_cam_msgs::msg::ProtectedZoneID::ProtectedZoneID( + const ProtectedZoneID& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::ProtectedZoneID::ProtectedZoneID( + ProtectedZoneID&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::ProtectedZoneID& etsi_its_cam_msgs::msg::ProtectedZoneID::operator =( + const ProtectedZoneID& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::ProtectedZoneID& etsi_its_cam_msgs::msg::ProtectedZoneID::operator =( + ProtectedZoneID&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::ProtectedZoneID::operator ==( + const ProtectedZoneID& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::ProtectedZoneID::operator !=( + const ProtectedZoneID& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::ProtectedZoneID::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::ProtectedZoneID::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::ProtectedZoneID& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::ProtectedZoneID::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::ProtectedZoneID::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::ProtectedZoneID::value( + uint32_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint32_t etsi_its_cam_msgs::msg::ProtectedZoneID::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint32_t& etsi_its_cam_msgs::msg::ProtectedZoneID::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::ProtectedZoneID::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::ProtectedZoneID::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::ProtectedZoneID::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneID.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneID.h new file mode 100644 index 00000000000..bd96dee41a8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneID.h @@ -0,0 +1,214 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ProtectedZoneID.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONEID_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONEID_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(ProtectedZoneID_SOURCE) +#define ProtectedZoneID_DllAPI __declspec( dllexport ) +#else +#define ProtectedZoneID_DllAPI __declspec( dllimport ) +#endif // ProtectedZoneID_SOURCE +#else +#define ProtectedZoneID_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define ProtectedZoneID_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace ProtectedZoneID_Constants { + const uint32_t MIN = 0; + const uint32_t MAX = 134217727; + } // namespace ProtectedZoneID_Constants + /*! + * @brief This class represents the structure ProtectedZoneID defined by the user in the IDL file. + * @ingroup PROTECTEDZONEID + */ + class ProtectedZoneID + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport ProtectedZoneID(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~ProtectedZoneID(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::ProtectedZoneID that will be copied. + */ + eProsima_user_DllExport ProtectedZoneID( + const ProtectedZoneID& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::ProtectedZoneID that will be copied. + */ + eProsima_user_DllExport ProtectedZoneID( + ProtectedZoneID&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::ProtectedZoneID that will be copied. + */ + eProsima_user_DllExport ProtectedZoneID& operator =( + const ProtectedZoneID& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::ProtectedZoneID that will be copied. + */ + eProsima_user_DllExport ProtectedZoneID& operator =( + ProtectedZoneID&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::ProtectedZoneID object to compare. + */ + eProsima_user_DllExport bool operator ==( + const ProtectedZoneID& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::ProtectedZoneID object to compare. + */ + eProsima_user_DllExport bool operator !=( + const ProtectedZoneID& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint32_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint32_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint32_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::ProtectedZoneID& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint32_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONEID_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneIDPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneIDPubSubTypes.cxx new file mode 100644 index 00000000000..34adbbefba3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneIDPubSubTypes.cxx @@ -0,0 +1,181 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ProtectedZoneIDPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "ProtectedZoneIDPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace ProtectedZoneID_Constants { + + + + } //End of namespace ProtectedZoneID_Constants + ProtectedZoneIDPubSubType::ProtectedZoneIDPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::ProtectedZoneID_"); + auto type_size = ProtectedZoneID::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = ProtectedZoneID::isKeyDefined(); + size_t keyLength = ProtectedZoneID::getKeyMaxCdrSerializedSize() > 16 ? + ProtectedZoneID::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + ProtectedZoneIDPubSubType::~ProtectedZoneIDPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool ProtectedZoneIDPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + ProtectedZoneID* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool ProtectedZoneIDPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + ProtectedZoneID* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function ProtectedZoneIDPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* ProtectedZoneIDPubSubType::createData() + { + return reinterpret_cast(new ProtectedZoneID()); + } + + void ProtectedZoneIDPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool ProtectedZoneIDPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + ProtectedZoneID* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + ProtectedZoneID::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || ProtectedZoneID::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneIDPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneIDPubSubTypes.h new file mode 100644 index 00000000000..90766eb715b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneIDPubSubTypes.h @@ -0,0 +1,112 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ProtectedZoneIDPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONEID_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONEID_PUBSUBTYPES_H_ + +#include +#include + +#include "ProtectedZoneID.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated ProtectedZoneID is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace ProtectedZoneID_Constants + { + + + } + /*! + * @brief This class represents the TopicDataType of the type ProtectedZoneID defined by the user in the IDL file. + * @ingroup PROTECTEDZONEID + */ + class ProtectedZoneIDPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef ProtectedZoneID type; + + eProsima_user_DllExport ProtectedZoneIDPubSubType(); + + eProsima_user_DllExport virtual ~ProtectedZoneIDPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) ProtectedZoneID(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONEID_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadius.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadius.cxx new file mode 100644 index 00000000000..9323631b461 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadius.cxx @@ -0,0 +1,187 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ProtectedZoneRadius.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "ProtectedZoneRadius.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + +etsi_its_cam_msgs::msg::ProtectedZoneRadius::ProtectedZoneRadius() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@5d10455d + m_value = 0; + +} + +etsi_its_cam_msgs::msg::ProtectedZoneRadius::~ProtectedZoneRadius() +{ +} + +etsi_its_cam_msgs::msg::ProtectedZoneRadius::ProtectedZoneRadius( + const ProtectedZoneRadius& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::ProtectedZoneRadius::ProtectedZoneRadius( + ProtectedZoneRadius&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::ProtectedZoneRadius& etsi_its_cam_msgs::msg::ProtectedZoneRadius::operator =( + const ProtectedZoneRadius& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::ProtectedZoneRadius& etsi_its_cam_msgs::msg::ProtectedZoneRadius::operator =( + ProtectedZoneRadius&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::ProtectedZoneRadius::operator ==( + const ProtectedZoneRadius& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::ProtectedZoneRadius::operator !=( + const ProtectedZoneRadius& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::ProtectedZoneRadius::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::ProtectedZoneRadius::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::ProtectedZoneRadius& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::ProtectedZoneRadius::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::ProtectedZoneRadius::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::ProtectedZoneRadius::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::ProtectedZoneRadius::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::ProtectedZoneRadius::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::ProtectedZoneRadius::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::ProtectedZoneRadius::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::ProtectedZoneRadius::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadius.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadius.h new file mode 100644 index 00000000000..d0a2628481b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadius.h @@ -0,0 +1,215 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ProtectedZoneRadius.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONERADIUS_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONERADIUS_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(ProtectedZoneRadius_SOURCE) +#define ProtectedZoneRadius_DllAPI __declspec( dllexport ) +#else +#define ProtectedZoneRadius_DllAPI __declspec( dllimport ) +#endif // ProtectedZoneRadius_SOURCE +#else +#define ProtectedZoneRadius_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define ProtectedZoneRadius_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace ProtectedZoneRadius_Constants { + const uint8_t MIN = 1; + const uint8_t MAX = 255; + const uint8_t ONE_METER = 1; + } // namespace ProtectedZoneRadius_Constants + /*! + * @brief This class represents the structure ProtectedZoneRadius defined by the user in the IDL file. + * @ingroup PROTECTEDZONERADIUS + */ + class ProtectedZoneRadius + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport ProtectedZoneRadius(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~ProtectedZoneRadius(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::ProtectedZoneRadius that will be copied. + */ + eProsima_user_DllExport ProtectedZoneRadius( + const ProtectedZoneRadius& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::ProtectedZoneRadius that will be copied. + */ + eProsima_user_DllExport ProtectedZoneRadius( + ProtectedZoneRadius&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::ProtectedZoneRadius that will be copied. + */ + eProsima_user_DllExport ProtectedZoneRadius& operator =( + const ProtectedZoneRadius& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::ProtectedZoneRadius that will be copied. + */ + eProsima_user_DllExport ProtectedZoneRadius& operator =( + ProtectedZoneRadius&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::ProtectedZoneRadius object to compare. + */ + eProsima_user_DllExport bool operator ==( + const ProtectedZoneRadius& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::ProtectedZoneRadius object to compare. + */ + eProsima_user_DllExport bool operator !=( + const ProtectedZoneRadius& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::ProtectedZoneRadius& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONERADIUS_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadiusPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadiusPubSubTypes.cxx new file mode 100644 index 00000000000..47a1fd3168d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadiusPubSubTypes.cxx @@ -0,0 +1,182 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ProtectedZoneRadiusPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "ProtectedZoneRadiusPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace ProtectedZoneRadius_Constants { + + + + + } //End of namespace ProtectedZoneRadius_Constants + ProtectedZoneRadiusPubSubType::ProtectedZoneRadiusPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::ProtectedZoneRadius_"); + auto type_size = ProtectedZoneRadius::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = ProtectedZoneRadius::isKeyDefined(); + size_t keyLength = ProtectedZoneRadius::getKeyMaxCdrSerializedSize() > 16 ? + ProtectedZoneRadius::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + ProtectedZoneRadiusPubSubType::~ProtectedZoneRadiusPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool ProtectedZoneRadiusPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + ProtectedZoneRadius* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool ProtectedZoneRadiusPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + ProtectedZoneRadius* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function ProtectedZoneRadiusPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* ProtectedZoneRadiusPubSubType::createData() + { + return reinterpret_cast(new ProtectedZoneRadius()); + } + + void ProtectedZoneRadiusPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool ProtectedZoneRadiusPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + ProtectedZoneRadius* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + ProtectedZoneRadius::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || ProtectedZoneRadius::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadiusPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadiusPubSubTypes.h new file mode 100644 index 00000000000..4fac8e2db05 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadiusPubSubTypes.h @@ -0,0 +1,113 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ProtectedZoneRadiusPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONERADIUS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONERADIUS_PUBSUBTYPES_H_ + +#include +#include + +#include "ProtectedZoneRadius.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated ProtectedZoneRadius is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace ProtectedZoneRadius_Constants + { + + + + } + /*! + * @brief This class represents the TopicDataType of the type ProtectedZoneRadius defined by the user in the IDL file. + * @ingroup PROTECTEDZONERADIUS + */ + class ProtectedZoneRadiusPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef ProtectedZoneRadius type; + + eProsima_user_DllExport ProtectedZoneRadiusPubSubType(); + + eProsima_user_DllExport virtual ~ProtectedZoneRadiusPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) ProtectedZoneRadius(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONERADIUS_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneType.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneType.cxx new file mode 100644 index 00000000000..4781e2f54b9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneType.cxx @@ -0,0 +1,186 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ProtectedZoneType.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "ProtectedZoneType.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + +etsi_its_cam_msgs::msg::ProtectedZoneType::ProtectedZoneType() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@737edcfa + m_value = 0; + +} + +etsi_its_cam_msgs::msg::ProtectedZoneType::~ProtectedZoneType() +{ +} + +etsi_its_cam_msgs::msg::ProtectedZoneType::ProtectedZoneType( + const ProtectedZoneType& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::ProtectedZoneType::ProtectedZoneType( + ProtectedZoneType&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::ProtectedZoneType& etsi_its_cam_msgs::msg::ProtectedZoneType::operator =( + const ProtectedZoneType& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::ProtectedZoneType& etsi_its_cam_msgs::msg::ProtectedZoneType::operator =( + ProtectedZoneType&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::ProtectedZoneType::operator ==( + const ProtectedZoneType& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::ProtectedZoneType::operator !=( + const ProtectedZoneType& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::ProtectedZoneType::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::ProtectedZoneType::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::ProtectedZoneType& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::ProtectedZoneType::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::ProtectedZoneType::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::ProtectedZoneType::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::ProtectedZoneType::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::ProtectedZoneType::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::ProtectedZoneType::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::ProtectedZoneType::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::ProtectedZoneType::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneType.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneType.h new file mode 100644 index 00000000000..dd9651a4c8c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneType.h @@ -0,0 +1,214 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ProtectedZoneType.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONETYPE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONETYPE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(ProtectedZoneType_SOURCE) +#define ProtectedZoneType_DllAPI __declspec( dllexport ) +#else +#define ProtectedZoneType_DllAPI __declspec( dllimport ) +#endif // ProtectedZoneType_SOURCE +#else +#define ProtectedZoneType_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define ProtectedZoneType_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace ProtectedZoneType_Constants { + const uint8_t PERMANENT_CEN_DSRC_TOLLING = 0; + const uint8_t TEMPORARY_CEN_DSRC_TOLLING = 1; + } // namespace ProtectedZoneType_Constants + /*! + * @brief This class represents the structure ProtectedZoneType defined by the user in the IDL file. + * @ingroup PROTECTEDZONETYPE + */ + class ProtectedZoneType + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport ProtectedZoneType(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~ProtectedZoneType(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::ProtectedZoneType that will be copied. + */ + eProsima_user_DllExport ProtectedZoneType( + const ProtectedZoneType& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::ProtectedZoneType that will be copied. + */ + eProsima_user_DllExport ProtectedZoneType( + ProtectedZoneType&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::ProtectedZoneType that will be copied. + */ + eProsima_user_DllExport ProtectedZoneType& operator =( + const ProtectedZoneType& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::ProtectedZoneType that will be copied. + */ + eProsima_user_DllExport ProtectedZoneType& operator =( + ProtectedZoneType&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::ProtectedZoneType object to compare. + */ + eProsima_user_DllExport bool operator ==( + const ProtectedZoneType& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::ProtectedZoneType object to compare. + */ + eProsima_user_DllExport bool operator !=( + const ProtectedZoneType& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::ProtectedZoneType& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONETYPE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneTypePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneTypePubSubTypes.cxx new file mode 100644 index 00000000000..4d699d8e58c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneTypePubSubTypes.cxx @@ -0,0 +1,181 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ProtectedZoneTypePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "ProtectedZoneTypePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace ProtectedZoneType_Constants { + + + + } //End of namespace ProtectedZoneType_Constants + ProtectedZoneTypePubSubType::ProtectedZoneTypePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::ProtectedZoneType_"); + auto type_size = ProtectedZoneType::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = ProtectedZoneType::isKeyDefined(); + size_t keyLength = ProtectedZoneType::getKeyMaxCdrSerializedSize() > 16 ? + ProtectedZoneType::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + ProtectedZoneTypePubSubType::~ProtectedZoneTypePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool ProtectedZoneTypePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + ProtectedZoneType* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool ProtectedZoneTypePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + ProtectedZoneType* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function ProtectedZoneTypePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* ProtectedZoneTypePubSubType::createData() + { + return reinterpret_cast(new ProtectedZoneType()); + } + + void ProtectedZoneTypePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool ProtectedZoneTypePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + ProtectedZoneType* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + ProtectedZoneType::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || ProtectedZoneType::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneTypePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneTypePubSubTypes.h new file mode 100644 index 00000000000..51a1dfa6fc9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneTypePubSubTypes.h @@ -0,0 +1,112 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ProtectedZoneTypePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONETYPE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONETYPE_PUBSUBTYPES_H_ + +#include +#include + +#include "ProtectedZoneType.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated ProtectedZoneType is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace ProtectedZoneType_Constants + { + + + } + /*! + * @brief This class represents the TopicDataType of the type ProtectedZoneType defined by the user in the IDL file. + * @ingroup PROTECTEDZONETYPE + */ + class ProtectedZoneTypePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef ProtectedZoneType type; + + eProsima_user_DllExport ProtectedZoneTypePubSubType(); + + eProsima_user_DllExport virtual ~ProtectedZoneTypePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) ProtectedZoneType(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONETYPE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivation.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivation.cxx new file mode 100644 index 00000000000..bc7179b20a9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivation.cxx @@ -0,0 +1,238 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PtActivation.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "PtActivation.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::PtActivation::PtActivation() +{ + // m_pt_activation_type com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@4a9cc6cb + + // m_pt_activation_data com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@5990e6c5 + + +} + +etsi_its_cam_msgs::msg::PtActivation::~PtActivation() +{ + +} + +etsi_its_cam_msgs::msg::PtActivation::PtActivation( + const PtActivation& x) +{ + m_pt_activation_type = x.m_pt_activation_type; + m_pt_activation_data = x.m_pt_activation_data; +} + +etsi_its_cam_msgs::msg::PtActivation::PtActivation( + PtActivation&& x) +{ + m_pt_activation_type = std::move(x.m_pt_activation_type); + m_pt_activation_data = std::move(x.m_pt_activation_data); +} + +etsi_its_cam_msgs::msg::PtActivation& etsi_its_cam_msgs::msg::PtActivation::operator =( + const PtActivation& x) +{ + + m_pt_activation_type = x.m_pt_activation_type; + m_pt_activation_data = x.m_pt_activation_data; + + return *this; +} + +etsi_its_cam_msgs::msg::PtActivation& etsi_its_cam_msgs::msg::PtActivation::operator =( + PtActivation&& x) +{ + + m_pt_activation_type = std::move(x.m_pt_activation_type); + m_pt_activation_data = std::move(x.m_pt_activation_data); + + return *this; +} + +bool etsi_its_cam_msgs::msg::PtActivation::operator ==( + const PtActivation& x) const +{ + + return (m_pt_activation_type == x.m_pt_activation_type && m_pt_activation_data == x.m_pt_activation_data); +} + +bool etsi_its_cam_msgs::msg::PtActivation::operator !=( + const PtActivation& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::PtActivation::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::PtActivationType::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::PtActivationData::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::PtActivation::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::PtActivation& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::PtActivationType::getCdrSerializedSize(data.pt_activation_type(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::PtActivationData::getCdrSerializedSize(data.pt_activation_data(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::PtActivation::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_pt_activation_type; + scdr << m_pt_activation_data; + +} + +void etsi_its_cam_msgs::msg::PtActivation::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_pt_activation_type; + dcdr >> m_pt_activation_data; +} + +/*! + * @brief This function copies the value in member pt_activation_type + * @param _pt_activation_type New value to be copied in member pt_activation_type + */ +void etsi_its_cam_msgs::msg::PtActivation::pt_activation_type( + const etsi_its_cam_msgs::msg::PtActivationType& _pt_activation_type) +{ + m_pt_activation_type = _pt_activation_type; +} + +/*! + * @brief This function moves the value in member pt_activation_type + * @param _pt_activation_type New value to be moved in member pt_activation_type + */ +void etsi_its_cam_msgs::msg::PtActivation::pt_activation_type( + etsi_its_cam_msgs::msg::PtActivationType&& _pt_activation_type) +{ + m_pt_activation_type = std::move(_pt_activation_type); +} + +/*! + * @brief This function returns a constant reference to member pt_activation_type + * @return Constant reference to member pt_activation_type + */ +const etsi_its_cam_msgs::msg::PtActivationType& etsi_its_cam_msgs::msg::PtActivation::pt_activation_type() const +{ + return m_pt_activation_type; +} + +/*! + * @brief This function returns a reference to member pt_activation_type + * @return Reference to member pt_activation_type + */ +etsi_its_cam_msgs::msg::PtActivationType& etsi_its_cam_msgs::msg::PtActivation::pt_activation_type() +{ + return m_pt_activation_type; +} +/*! + * @brief This function copies the value in member pt_activation_data + * @param _pt_activation_data New value to be copied in member pt_activation_data + */ +void etsi_its_cam_msgs::msg::PtActivation::pt_activation_data( + const etsi_its_cam_msgs::msg::PtActivationData& _pt_activation_data) +{ + m_pt_activation_data = _pt_activation_data; +} + +/*! + * @brief This function moves the value in member pt_activation_data + * @param _pt_activation_data New value to be moved in member pt_activation_data + */ +void etsi_its_cam_msgs::msg::PtActivation::pt_activation_data( + etsi_its_cam_msgs::msg::PtActivationData&& _pt_activation_data) +{ + m_pt_activation_data = std::move(_pt_activation_data); +} + +/*! + * @brief This function returns a constant reference to member pt_activation_data + * @return Constant reference to member pt_activation_data + */ +const etsi_its_cam_msgs::msg::PtActivationData& etsi_its_cam_msgs::msg::PtActivation::pt_activation_data() const +{ + return m_pt_activation_data; +} + +/*! + * @brief This function returns a reference to member pt_activation_data + * @return Reference to member pt_activation_data + */ +etsi_its_cam_msgs::msg::PtActivationData& etsi_its_cam_msgs::msg::PtActivation::pt_activation_data() +{ + return m_pt_activation_data; +} + +size_t etsi_its_cam_msgs::msg::PtActivation::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::PtActivation::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::PtActivation::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivation.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivation.h new file mode 100644 index 00000000000..fc2c86d68bd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivation.h @@ -0,0 +1,244 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PtActivation.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATION_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATION_H_ + +#include "PtActivationData.h" +#include "PtActivationType.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(PtActivation_SOURCE) +#define PtActivation_DllAPI __declspec( dllexport ) +#else +#define PtActivation_DllAPI __declspec( dllimport ) +#endif // PtActivation_SOURCE +#else +#define PtActivation_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define PtActivation_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure PtActivation defined by the user in the IDL file. + * @ingroup PTACTIVATION + */ + class PtActivation + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport PtActivation(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~PtActivation(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::PtActivation that will be copied. + */ + eProsima_user_DllExport PtActivation( + const PtActivation& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::PtActivation that will be copied. + */ + eProsima_user_DllExport PtActivation( + PtActivation&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::PtActivation that will be copied. + */ + eProsima_user_DllExport PtActivation& operator =( + const PtActivation& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::PtActivation that will be copied. + */ + eProsima_user_DllExport PtActivation& operator =( + PtActivation&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::PtActivation object to compare. + */ + eProsima_user_DllExport bool operator ==( + const PtActivation& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::PtActivation object to compare. + */ + eProsima_user_DllExport bool operator !=( + const PtActivation& x) const; + + /*! + * @brief This function copies the value in member pt_activation_type + * @param _pt_activation_type New value to be copied in member pt_activation_type + */ + eProsima_user_DllExport void pt_activation_type( + const etsi_its_cam_msgs::msg::PtActivationType& _pt_activation_type); + + /*! + * @brief This function moves the value in member pt_activation_type + * @param _pt_activation_type New value to be moved in member pt_activation_type + */ + eProsima_user_DllExport void pt_activation_type( + etsi_its_cam_msgs::msg::PtActivationType&& _pt_activation_type); + + /*! + * @brief This function returns a constant reference to member pt_activation_type + * @return Constant reference to member pt_activation_type + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::PtActivationType& pt_activation_type() const; + + /*! + * @brief This function returns a reference to member pt_activation_type + * @return Reference to member pt_activation_type + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::PtActivationType& pt_activation_type(); + /*! + * @brief This function copies the value in member pt_activation_data + * @param _pt_activation_data New value to be copied in member pt_activation_data + */ + eProsima_user_DllExport void pt_activation_data( + const etsi_its_cam_msgs::msg::PtActivationData& _pt_activation_data); + + /*! + * @brief This function moves the value in member pt_activation_data + * @param _pt_activation_data New value to be moved in member pt_activation_data + */ + eProsima_user_DllExport void pt_activation_data( + etsi_its_cam_msgs::msg::PtActivationData&& _pt_activation_data); + + /*! + * @brief This function returns a constant reference to member pt_activation_data + * @return Constant reference to member pt_activation_data + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::PtActivationData& pt_activation_data() const; + + /*! + * @brief This function returns a reference to member pt_activation_data + * @return Reference to member pt_activation_data + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::PtActivationData& pt_activation_data(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::PtActivation& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::PtActivationType m_pt_activation_type; + etsi_its_cam_msgs::msg::PtActivationData m_pt_activation_data; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATION_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationData.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationData.cxx new file mode 100644 index 00000000000..aec6eb962a6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationData.cxx @@ -0,0 +1,202 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PtActivationData.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "PtActivationData.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + +etsi_its_cam_msgs::msg::PtActivationData::PtActivationData() +{ + // m_value com.eprosima.idl.parser.typecode.SequenceTypeCode@19b30c92 + + +} + +etsi_its_cam_msgs::msg::PtActivationData::~PtActivationData() +{ +} + +etsi_its_cam_msgs::msg::PtActivationData::PtActivationData( + const PtActivationData& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::PtActivationData::PtActivationData( + PtActivationData&& x) +{ + m_value = std::move(x.m_value); +} + +etsi_its_cam_msgs::msg::PtActivationData& etsi_its_cam_msgs::msg::PtActivationData::operator =( + const PtActivationData& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::PtActivationData& etsi_its_cam_msgs::msg::PtActivationData::operator =( + PtActivationData&& x) +{ + + m_value = std::move(x.m_value); + + return *this; +} + +bool etsi_its_cam_msgs::msg::PtActivationData::operator ==( + const PtActivationData& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::PtActivationData::operator !=( + const PtActivationData& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::PtActivationData::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + current_alignment += (100 * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::PtActivationData::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::PtActivationData& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + if (data.value().size() > 0) + { + current_alignment += (data.value().size() * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + } + + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::PtActivationData::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; +} + +void etsi_its_cam_msgs::msg::PtActivationData::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value;} + +/*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ +void etsi_its_cam_msgs::msg::PtActivationData::value( + const std::vector& _value) +{ + m_value = _value; +} + +/*! + * @brief This function moves the value in member value + * @param _value New value to be moved in member value + */ +void etsi_its_cam_msgs::msg::PtActivationData::value( + std::vector&& _value) +{ + m_value = std::move(_value); +} + +/*! + * @brief This function returns a constant reference to member value + * @return Constant reference to member value + */ +const std::vector& etsi_its_cam_msgs::msg::PtActivationData::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +std::vector& etsi_its_cam_msgs::msg::PtActivationData::value() +{ + return m_value; +} + +size_t etsi_its_cam_msgs::msg::PtActivationData::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::PtActivationData::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::PtActivationData::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationData.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationData.h new file mode 100644 index 00000000000..a5937220f4f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationData.h @@ -0,0 +1,220 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PtActivationData.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONDATA_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONDATA_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(PtActivationData_SOURCE) +#define PtActivationData_DllAPI __declspec( dllexport ) +#else +#define PtActivationData_DllAPI __declspec( dllimport ) +#endif // PtActivationData_SOURCE +#else +#define PtActivationData_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define PtActivationData_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace PtActivationData_Constants { + const uint8_t MIN_SIZE = 1; + const uint8_t MAX_SIZE = 20; + } // namespace PtActivationData_Constants + /*! + * @brief This class represents the structure PtActivationData defined by the user in the IDL file. + * @ingroup PTACTIVATIONDATA + */ + class PtActivationData + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport PtActivationData(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~PtActivationData(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::PtActivationData that will be copied. + */ + eProsima_user_DllExport PtActivationData( + const PtActivationData& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::PtActivationData that will be copied. + */ + eProsima_user_DllExport PtActivationData( + PtActivationData&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::PtActivationData that will be copied. + */ + eProsima_user_DllExport PtActivationData& operator =( + const PtActivationData& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::PtActivationData that will be copied. + */ + eProsima_user_DllExport PtActivationData& operator =( + PtActivationData&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::PtActivationData object to compare. + */ + eProsima_user_DllExport bool operator ==( + const PtActivationData& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::PtActivationData object to compare. + */ + eProsima_user_DllExport bool operator !=( + const PtActivationData& x) const; + + /*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ + eProsima_user_DllExport void value( + const std::vector& _value); + + /*! + * @brief This function moves the value in member value + * @param _value New value to be moved in member value + */ + eProsima_user_DllExport void value( + std::vector&& _value); + + /*! + * @brief This function returns a constant reference to member value + * @return Constant reference to member value + */ + eProsima_user_DllExport const std::vector& value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport std::vector& value(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::PtActivationData& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std::vector m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONDATA_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationDataPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationDataPubSubTypes.cxx new file mode 100644 index 00000000000..3c4e779ca23 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationDataPubSubTypes.cxx @@ -0,0 +1,181 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PtActivationDataPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "PtActivationDataPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace PtActivationData_Constants { + + + + } //End of namespace PtActivationData_Constants + PtActivationDataPubSubType::PtActivationDataPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::PtActivationData_"); + auto type_size = PtActivationData::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = PtActivationData::isKeyDefined(); + size_t keyLength = PtActivationData::getKeyMaxCdrSerializedSize() > 16 ? + PtActivationData::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + PtActivationDataPubSubType::~PtActivationDataPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool PtActivationDataPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + PtActivationData* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool PtActivationDataPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + PtActivationData* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function PtActivationDataPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* PtActivationDataPubSubType::createData() + { + return reinterpret_cast(new PtActivationData()); + } + + void PtActivationDataPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool PtActivationDataPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + PtActivationData* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + PtActivationData::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || PtActivationData::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/types/NavSatFixPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationDataPubSubTypes.h similarity index 75% rename from LibCarla/source/carla/ros2/types/NavSatFixPubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationDataPubSubTypes.h index d6bf7437198..d45d9f58488 100644 --- a/LibCarla/source/carla/ros2/types/NavSatFixPubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationDataPubSubTypes.h @@ -13,47 +13,48 @@ // limitations under the License. /*! - * @file NavSatFixPubSubTypes.h + * @file PtActivationDataPubSubTypes.h * This header file contains the declaration of the serialization functions. * * This file was generated by the tool fastcdrgen. */ -#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIX_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIX_PUBSUBTYPES_H_ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONDATA_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONDATA_PUBSUBTYPES_H_ #include #include -#include "NavSatFix.h" - -#include "HeaderPubSubTypes.h" -#include "NavSatStatusPubSubTypes.h" +#include "PtActivationData.h" #if !defined(GEN_API_VER) || (GEN_API_VER != 1) #error \ - Generated NavSatFix is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. + Generated PtActivationData is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. #endif // GEN_API_VER -namespace sensor_msgs +namespace etsi_its_cam_msgs { namespace msg { - typedef std::array sensor_msgs__NavSatFix__double_array_9; + namespace PtActivationData_Constants + { + + } /*! - * @brief This class represents the TopicDataType of the type NavSatFix defined by the user in the IDL file. - * @ingroup NAVSATFIX + * @brief This class represents the TopicDataType of the type PtActivationData defined by the user in the IDL file. + * @ingroup PTACTIVATIONDATA */ - class NavSatFixPubSubType : public eprosima::fastdds::dds::TopicDataType + class PtActivationDataPubSubType : public eprosima::fastdds::dds::TopicDataType { public: - typedef NavSatFix type; + typedef PtActivationData type; - eProsima_user_DllExport NavSatFixPubSubType(); + eProsima_user_DllExport PtActivationDataPubSubType(); - eProsima_user_DllExport virtual ~NavSatFixPubSubType() override; + eProsima_user_DllExport virtual ~PtActivationDataPubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -101,10 +102,11 @@ namespace sensor_msgs } #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; unsigned char* m_keyBuffer; }; } } -#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIX_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONDATA_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationPubSubTypes.cxx new file mode 100644 index 00000000000..f06978dd58a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PtActivationPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "PtActivationPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + PtActivationPubSubType::PtActivationPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::PtActivation_"); + auto type_size = PtActivation::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = PtActivation::isKeyDefined(); + size_t keyLength = PtActivation::getKeyMaxCdrSerializedSize() > 16 ? + PtActivation::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + PtActivationPubSubType::~PtActivationPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool PtActivationPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + PtActivation* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool PtActivationPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + PtActivation* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function PtActivationPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* PtActivationPubSubType::createData() + { + return reinterpret_cast(new PtActivation()); + } + + void PtActivationPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool PtActivationPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + PtActivation* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + PtActivation::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || PtActivation::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationPubSubTypes.h new file mode 100644 index 00000000000..fd5b438c09c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PtActivationPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATION_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATION_PUBSUBTYPES_H_ + +#include +#include + +#include "PtActivation.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated PtActivation is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type PtActivation defined by the user in the IDL file. + * @ingroup PTACTIVATION + */ + class PtActivationPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef PtActivation type; + + eProsima_user_DllExport PtActivationPubSubType(); + + eProsima_user_DllExport virtual ~PtActivationPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATION_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationType.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationType.cxx new file mode 100644 index 00000000000..cc5fbc605a2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationType.cxx @@ -0,0 +1,189 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PtActivationType.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "PtActivationType.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + +etsi_its_cam_msgs::msg::PtActivationType::PtActivationType() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@782a4fff + m_value = 0; + +} + +etsi_its_cam_msgs::msg::PtActivationType::~PtActivationType() +{ +} + +etsi_its_cam_msgs::msg::PtActivationType::PtActivationType( + const PtActivationType& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::PtActivationType::PtActivationType( + PtActivationType&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::PtActivationType& etsi_its_cam_msgs::msg::PtActivationType::operator =( + const PtActivationType& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::PtActivationType& etsi_its_cam_msgs::msg::PtActivationType::operator =( + PtActivationType&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::PtActivationType::operator ==( + const PtActivationType& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::PtActivationType::operator !=( + const PtActivationType& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::PtActivationType::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::PtActivationType::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::PtActivationType& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::PtActivationType::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::PtActivationType::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::PtActivationType::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::PtActivationType::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::PtActivationType::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::PtActivationType::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::PtActivationType::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::PtActivationType::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationType.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationType.h new file mode 100644 index 00000000000..12a1b678381 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationType.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PtActivationType.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONTYPE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONTYPE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(PtActivationType_SOURCE) +#define PtActivationType_DllAPI __declspec( dllexport ) +#else +#define PtActivationType_DllAPI __declspec( dllimport ) +#endif // PtActivationType_SOURCE +#else +#define PtActivationType_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define PtActivationType_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace PtActivationType_Constants { + const uint8_t MIN = 0; + const uint8_t MAX = 255; + const uint8_t UNDEFINED_CODING_TYPE = 0; + const uint8_t R_09_16_CODING_TYPE = 1; + const uint8_t VDV_50149_CODING_TYPE = 2; + } // namespace PtActivationType_Constants + /*! + * @brief This class represents the structure PtActivationType defined by the user in the IDL file. + * @ingroup PTACTIVATIONTYPE + */ + class PtActivationType + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport PtActivationType(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~PtActivationType(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::PtActivationType that will be copied. + */ + eProsima_user_DllExport PtActivationType( + const PtActivationType& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::PtActivationType that will be copied. + */ + eProsima_user_DllExport PtActivationType( + PtActivationType&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::PtActivationType that will be copied. + */ + eProsima_user_DllExport PtActivationType& operator =( + const PtActivationType& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::PtActivationType that will be copied. + */ + eProsima_user_DllExport PtActivationType& operator =( + PtActivationType&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::PtActivationType object to compare. + */ + eProsima_user_DllExport bool operator ==( + const PtActivationType& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::PtActivationType object to compare. + */ + eProsima_user_DllExport bool operator !=( + const PtActivationType& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::PtActivationType& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONTYPE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationTypePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationTypePubSubTypes.cxx new file mode 100644 index 00000000000..305a799c602 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationTypePubSubTypes.cxx @@ -0,0 +1,184 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PtActivationTypePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "PtActivationTypePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace PtActivationType_Constants { + + + + + + + } //End of namespace PtActivationType_Constants + PtActivationTypePubSubType::PtActivationTypePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::PtActivationType_"); + auto type_size = PtActivationType::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = PtActivationType::isKeyDefined(); + size_t keyLength = PtActivationType::getKeyMaxCdrSerializedSize() > 16 ? + PtActivationType::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + PtActivationTypePubSubType::~PtActivationTypePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool PtActivationTypePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + PtActivationType* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool PtActivationTypePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + PtActivationType* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function PtActivationTypePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* PtActivationTypePubSubType::createData() + { + return reinterpret_cast(new PtActivationType()); + } + + void PtActivationTypePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool PtActivationTypePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + PtActivationType* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + PtActivationType::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || PtActivationType::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationTypePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationTypePubSubTypes.h new file mode 100644 index 00000000000..595fd47df88 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationTypePubSubTypes.h @@ -0,0 +1,115 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PtActivationTypePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONTYPE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONTYPE_PUBSUBTYPES_H_ + +#include +#include + +#include "PtActivationType.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated PtActivationType is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace PtActivationType_Constants + { + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type PtActivationType defined by the user in the IDL file. + * @ingroup PTACTIVATIONTYPE + */ + class PtActivationTypePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef PtActivationType type; + + eProsima_user_DllExport PtActivationTypePubSubType(); + + eProsima_user_DllExport virtual ~PtActivationTypePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) PtActivationType(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONTYPE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainer.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainer.cxx new file mode 100644 index 00000000000..8c39b46f55d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainer.cxx @@ -0,0 +1,281 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PublicTransportContainer.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "PublicTransportContainer.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::PublicTransportContainer::PublicTransportContainer() +{ + // m_embarkation_status com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@b91d8c4 + + // m_pt_activation com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@4b6166aa + + // m_pt_activation_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@a77614d + m_pt_activation_is_present = false; + +} + +etsi_its_cam_msgs::msg::PublicTransportContainer::~PublicTransportContainer() +{ + + +} + +etsi_its_cam_msgs::msg::PublicTransportContainer::PublicTransportContainer( + const PublicTransportContainer& x) +{ + m_embarkation_status = x.m_embarkation_status; + m_pt_activation = x.m_pt_activation; + m_pt_activation_is_present = x.m_pt_activation_is_present; +} + +etsi_its_cam_msgs::msg::PublicTransportContainer::PublicTransportContainer( + PublicTransportContainer&& x) +{ + m_embarkation_status = std::move(x.m_embarkation_status); + m_pt_activation = std::move(x.m_pt_activation); + m_pt_activation_is_present = x.m_pt_activation_is_present; +} + +etsi_its_cam_msgs::msg::PublicTransportContainer& etsi_its_cam_msgs::msg::PublicTransportContainer::operator =( + const PublicTransportContainer& x) +{ + + m_embarkation_status = x.m_embarkation_status; + m_pt_activation = x.m_pt_activation; + m_pt_activation_is_present = x.m_pt_activation_is_present; + + return *this; +} + +etsi_its_cam_msgs::msg::PublicTransportContainer& etsi_its_cam_msgs::msg::PublicTransportContainer::operator =( + PublicTransportContainer&& x) +{ + + m_embarkation_status = std::move(x.m_embarkation_status); + m_pt_activation = std::move(x.m_pt_activation); + m_pt_activation_is_present = x.m_pt_activation_is_present; + + return *this; +} + +bool etsi_its_cam_msgs::msg::PublicTransportContainer::operator ==( + const PublicTransportContainer& x) const +{ + + return (m_embarkation_status == x.m_embarkation_status && m_pt_activation == x.m_pt_activation && m_pt_activation_is_present == x.m_pt_activation_is_present); +} + +bool etsi_its_cam_msgs::msg::PublicTransportContainer::operator !=( + const PublicTransportContainer& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::PublicTransportContainer::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::EmbarkationStatus::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::PtActivation::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::PublicTransportContainer::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::PublicTransportContainer& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::EmbarkationStatus::getCdrSerializedSize(data.embarkation_status(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::PtActivation::getCdrSerializedSize(data.pt_activation(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::PublicTransportContainer::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_embarkation_status; + scdr << m_pt_activation; + scdr << m_pt_activation_is_present; + +} + +void etsi_its_cam_msgs::msg::PublicTransportContainer::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_embarkation_status; + dcdr >> m_pt_activation; + dcdr >> m_pt_activation_is_present; +} + +/*! + * @brief This function copies the value in member embarkation_status + * @param _embarkation_status New value to be copied in member embarkation_status + */ +void etsi_its_cam_msgs::msg::PublicTransportContainer::embarkation_status( + const etsi_its_cam_msgs::msg::EmbarkationStatus& _embarkation_status) +{ + m_embarkation_status = _embarkation_status; +} + +/*! + * @brief This function moves the value in member embarkation_status + * @param _embarkation_status New value to be moved in member embarkation_status + */ +void etsi_its_cam_msgs::msg::PublicTransportContainer::embarkation_status( + etsi_its_cam_msgs::msg::EmbarkationStatus&& _embarkation_status) +{ + m_embarkation_status = std::move(_embarkation_status); +} + +/*! + * @brief This function returns a constant reference to member embarkation_status + * @return Constant reference to member embarkation_status + */ +const etsi_its_cam_msgs::msg::EmbarkationStatus& etsi_its_cam_msgs::msg::PublicTransportContainer::embarkation_status() const +{ + return m_embarkation_status; +} + +/*! + * @brief This function returns a reference to member embarkation_status + * @return Reference to member embarkation_status + */ +etsi_its_cam_msgs::msg::EmbarkationStatus& etsi_its_cam_msgs::msg::PublicTransportContainer::embarkation_status() +{ + return m_embarkation_status; +} +/*! + * @brief This function copies the value in member pt_activation + * @param _pt_activation New value to be copied in member pt_activation + */ +void etsi_its_cam_msgs::msg::PublicTransportContainer::pt_activation( + const etsi_its_cam_msgs::msg::PtActivation& _pt_activation) +{ + m_pt_activation = _pt_activation; +} + +/*! + * @brief This function moves the value in member pt_activation + * @param _pt_activation New value to be moved in member pt_activation + */ +void etsi_its_cam_msgs::msg::PublicTransportContainer::pt_activation( + etsi_its_cam_msgs::msg::PtActivation&& _pt_activation) +{ + m_pt_activation = std::move(_pt_activation); +} + +/*! + * @brief This function returns a constant reference to member pt_activation + * @return Constant reference to member pt_activation + */ +const etsi_its_cam_msgs::msg::PtActivation& etsi_its_cam_msgs::msg::PublicTransportContainer::pt_activation() const +{ + return m_pt_activation; +} + +/*! + * @brief This function returns a reference to member pt_activation + * @return Reference to member pt_activation + */ +etsi_its_cam_msgs::msg::PtActivation& etsi_its_cam_msgs::msg::PublicTransportContainer::pt_activation() +{ + return m_pt_activation; +} +/*! + * @brief This function sets a value in member pt_activation_is_present + * @param _pt_activation_is_present New value for member pt_activation_is_present + */ +void etsi_its_cam_msgs::msg::PublicTransportContainer::pt_activation_is_present( + bool _pt_activation_is_present) +{ + m_pt_activation_is_present = _pt_activation_is_present; +} + +/*! + * @brief This function returns the value of member pt_activation_is_present + * @return Value of member pt_activation_is_present + */ +bool etsi_its_cam_msgs::msg::PublicTransportContainer::pt_activation_is_present() const +{ + return m_pt_activation_is_present; +} + +/*! + * @brief This function returns a reference to member pt_activation_is_present + * @return Reference to member pt_activation_is_present + */ +bool& etsi_its_cam_msgs::msg::PublicTransportContainer::pt_activation_is_present() +{ + return m_pt_activation_is_present; +} + + +size_t etsi_its_cam_msgs::msg::PublicTransportContainer::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::PublicTransportContainer::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::PublicTransportContainer::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainer.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainer.h new file mode 100644 index 00000000000..225aea3b44d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainer.h @@ -0,0 +1,264 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PublicTransportContainer.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PUBLICTRANSPORTCONTAINER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PUBLICTRANSPORTCONTAINER_H_ + +#include "PtActivation.h" +#include "EmbarkationStatus.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(PublicTransportContainer_SOURCE) +#define PublicTransportContainer_DllAPI __declspec( dllexport ) +#else +#define PublicTransportContainer_DllAPI __declspec( dllimport ) +#endif // PublicTransportContainer_SOURCE +#else +#define PublicTransportContainer_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define PublicTransportContainer_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure PublicTransportContainer defined by the user in the IDL file. + * @ingroup PUBLICTRANSPORTCONTAINER + */ + class PublicTransportContainer + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport PublicTransportContainer(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~PublicTransportContainer(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::PublicTransportContainer that will be copied. + */ + eProsima_user_DllExport PublicTransportContainer( + const PublicTransportContainer& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::PublicTransportContainer that will be copied. + */ + eProsima_user_DllExport PublicTransportContainer( + PublicTransportContainer&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::PublicTransportContainer that will be copied. + */ + eProsima_user_DllExport PublicTransportContainer& operator =( + const PublicTransportContainer& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::PublicTransportContainer that will be copied. + */ + eProsima_user_DllExport PublicTransportContainer& operator =( + PublicTransportContainer&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::PublicTransportContainer object to compare. + */ + eProsima_user_DllExport bool operator ==( + const PublicTransportContainer& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::PublicTransportContainer object to compare. + */ + eProsima_user_DllExport bool operator !=( + const PublicTransportContainer& x) const; + + /*! + * @brief This function copies the value in member embarkation_status + * @param _embarkation_status New value to be copied in member embarkation_status + */ + eProsima_user_DllExport void embarkation_status( + const etsi_its_cam_msgs::msg::EmbarkationStatus& _embarkation_status); + + /*! + * @brief This function moves the value in member embarkation_status + * @param _embarkation_status New value to be moved in member embarkation_status + */ + eProsima_user_DllExport void embarkation_status( + etsi_its_cam_msgs::msg::EmbarkationStatus&& _embarkation_status); + + /*! + * @brief This function returns a constant reference to member embarkation_status + * @return Constant reference to member embarkation_status + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::EmbarkationStatus& embarkation_status() const; + + /*! + * @brief This function returns a reference to member embarkation_status + * @return Reference to member embarkation_status + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::EmbarkationStatus& embarkation_status(); + /*! + * @brief This function copies the value in member pt_activation + * @param _pt_activation New value to be copied in member pt_activation + */ + eProsima_user_DllExport void pt_activation( + const etsi_its_cam_msgs::msg::PtActivation& _pt_activation); + + /*! + * @brief This function moves the value in member pt_activation + * @param _pt_activation New value to be moved in member pt_activation + */ + eProsima_user_DllExport void pt_activation( + etsi_its_cam_msgs::msg::PtActivation&& _pt_activation); + + /*! + * @brief This function returns a constant reference to member pt_activation + * @return Constant reference to member pt_activation + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::PtActivation& pt_activation() const; + + /*! + * @brief This function returns a reference to member pt_activation + * @return Reference to member pt_activation + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::PtActivation& pt_activation(); + /*! + * @brief This function sets a value in member pt_activation_is_present + * @param _pt_activation_is_present New value for member pt_activation_is_present + */ + eProsima_user_DllExport void pt_activation_is_present( + bool _pt_activation_is_present); + + /*! + * @brief This function returns the value of member pt_activation_is_present + * @return Value of member pt_activation_is_present + */ + eProsima_user_DllExport bool pt_activation_is_present() const; + + /*! + * @brief This function returns a reference to member pt_activation_is_present + * @return Reference to member pt_activation_is_present + */ + eProsima_user_DllExport bool& pt_activation_is_present(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::PublicTransportContainer& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::EmbarkationStatus m_embarkation_status; + etsi_its_cam_msgs::msg::PtActivation m_pt_activation; + bool m_pt_activation_is_present; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PUBLICTRANSPORTCONTAINER_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainerPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainerPubSubTypes.cxx new file mode 100644 index 00000000000..ad910cfd9dd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainerPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PublicTransportContainerPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "PublicTransportContainerPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + PublicTransportContainerPubSubType::PublicTransportContainerPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::PublicTransportContainer_"); + auto type_size = PublicTransportContainer::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = PublicTransportContainer::isKeyDefined(); + size_t keyLength = PublicTransportContainer::getKeyMaxCdrSerializedSize() > 16 ? + PublicTransportContainer::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + PublicTransportContainerPubSubType::~PublicTransportContainerPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool PublicTransportContainerPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + PublicTransportContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool PublicTransportContainerPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + PublicTransportContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function PublicTransportContainerPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* PublicTransportContainerPubSubType::createData() + { + return reinterpret_cast(new PublicTransportContainer()); + } + + void PublicTransportContainerPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool PublicTransportContainerPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + PublicTransportContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + PublicTransportContainer::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || PublicTransportContainer::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainerPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainerPubSubTypes.h new file mode 100644 index 00000000000..433d4a470bc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainerPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PublicTransportContainerPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PUBLICTRANSPORTCONTAINER_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PUBLICTRANSPORTCONTAINER_PUBSUBTYPES_H_ + +#include +#include + +#include "PublicTransportContainer.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated PublicTransportContainer is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type PublicTransportContainer defined by the user in the IDL file. + * @ingroup PUBLICTRANSPORTCONTAINER + */ + class PublicTransportContainerPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef PublicTransportContainer type; + + eProsima_user_DllExport PublicTransportContainerPubSubType(); + + eProsima_user_DllExport virtual ~PublicTransportContainerPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PUBLICTRANSPORTCONTAINER_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.cxx new file mode 100644 index 00000000000..31ad3448e61 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.cxx @@ -0,0 +1,233 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file RSUContainerHighFrequency.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "RSUContainerHighFrequency.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::RSUContainerHighFrequency::RSUContainerHighFrequency() +{ + // m_protected_communication_zones_rsu com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@20765ed5 + + // m_protected_communication_zones_rsu_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@3b582111 + m_protected_communication_zones_rsu_is_present = false; + +} + +etsi_its_cam_msgs::msg::RSUContainerHighFrequency::~RSUContainerHighFrequency() +{ + +} + +etsi_its_cam_msgs::msg::RSUContainerHighFrequency::RSUContainerHighFrequency( + const RSUContainerHighFrequency& x) +{ + m_protected_communication_zones_rsu = x.m_protected_communication_zones_rsu; + m_protected_communication_zones_rsu_is_present = x.m_protected_communication_zones_rsu_is_present; +} + +etsi_its_cam_msgs::msg::RSUContainerHighFrequency::RSUContainerHighFrequency( + RSUContainerHighFrequency&& x) +{ + m_protected_communication_zones_rsu = std::move(x.m_protected_communication_zones_rsu); + m_protected_communication_zones_rsu_is_present = x.m_protected_communication_zones_rsu_is_present; +} + +etsi_its_cam_msgs::msg::RSUContainerHighFrequency& etsi_its_cam_msgs::msg::RSUContainerHighFrequency::operator =( + const RSUContainerHighFrequency& x) +{ + + m_protected_communication_zones_rsu = x.m_protected_communication_zones_rsu; + m_protected_communication_zones_rsu_is_present = x.m_protected_communication_zones_rsu_is_present; + + return *this; +} + +etsi_its_cam_msgs::msg::RSUContainerHighFrequency& etsi_its_cam_msgs::msg::RSUContainerHighFrequency::operator =( + RSUContainerHighFrequency&& x) +{ + + m_protected_communication_zones_rsu = std::move(x.m_protected_communication_zones_rsu); + m_protected_communication_zones_rsu_is_present = x.m_protected_communication_zones_rsu_is_present; + + return *this; +} + +bool etsi_its_cam_msgs::msg::RSUContainerHighFrequency::operator ==( + const RSUContainerHighFrequency& x) const +{ + + return (m_protected_communication_zones_rsu == x.m_protected_communication_zones_rsu && m_protected_communication_zones_rsu_is_present == x.m_protected_communication_zones_rsu_is_present); +} + +bool etsi_its_cam_msgs::msg::RSUContainerHighFrequency::operator !=( + const RSUContainerHighFrequency& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::RSUContainerHighFrequency::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::RSUContainerHighFrequency::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::RSUContainerHighFrequency& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU::getCdrSerializedSize(data.protected_communication_zones_rsu(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::RSUContainerHighFrequency::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_protected_communication_zones_rsu; + scdr << m_protected_communication_zones_rsu_is_present; + +} + +void etsi_its_cam_msgs::msg::RSUContainerHighFrequency::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_protected_communication_zones_rsu; + dcdr >> m_protected_communication_zones_rsu_is_present; +} + +/*! + * @brief This function copies the value in member protected_communication_zones_rsu + * @param _protected_communication_zones_rsu New value to be copied in member protected_communication_zones_rsu + */ +void etsi_its_cam_msgs::msg::RSUContainerHighFrequency::protected_communication_zones_rsu( + const etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU& _protected_communication_zones_rsu) +{ + m_protected_communication_zones_rsu = _protected_communication_zones_rsu; +} + +/*! + * @brief This function moves the value in member protected_communication_zones_rsu + * @param _protected_communication_zones_rsu New value to be moved in member protected_communication_zones_rsu + */ +void etsi_its_cam_msgs::msg::RSUContainerHighFrequency::protected_communication_zones_rsu( + etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU&& _protected_communication_zones_rsu) +{ + m_protected_communication_zones_rsu = std::move(_protected_communication_zones_rsu); +} + +/*! + * @brief This function returns a constant reference to member protected_communication_zones_rsu + * @return Constant reference to member protected_communication_zones_rsu + */ +const etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU& etsi_its_cam_msgs::msg::RSUContainerHighFrequency::protected_communication_zones_rsu() const +{ + return m_protected_communication_zones_rsu; +} + +/*! + * @brief This function returns a reference to member protected_communication_zones_rsu + * @return Reference to member protected_communication_zones_rsu + */ +etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU& etsi_its_cam_msgs::msg::RSUContainerHighFrequency::protected_communication_zones_rsu() +{ + return m_protected_communication_zones_rsu; +} +/*! + * @brief This function sets a value in member protected_communication_zones_rsu_is_present + * @param _protected_communication_zones_rsu_is_present New value for member protected_communication_zones_rsu_is_present + */ +void etsi_its_cam_msgs::msg::RSUContainerHighFrequency::protected_communication_zones_rsu_is_present( + bool _protected_communication_zones_rsu_is_present) +{ + m_protected_communication_zones_rsu_is_present = _protected_communication_zones_rsu_is_present; +} + +/*! + * @brief This function returns the value of member protected_communication_zones_rsu_is_present + * @return Value of member protected_communication_zones_rsu_is_present + */ +bool etsi_its_cam_msgs::msg::RSUContainerHighFrequency::protected_communication_zones_rsu_is_present() const +{ + return m_protected_communication_zones_rsu_is_present; +} + +/*! + * @brief This function returns a reference to member protected_communication_zones_rsu_is_present + * @return Reference to member protected_communication_zones_rsu_is_present + */ +bool& etsi_its_cam_msgs::msg::RSUContainerHighFrequency::protected_communication_zones_rsu_is_present() +{ + return m_protected_communication_zones_rsu_is_present; +} + + +size_t etsi_its_cam_msgs::msg::RSUContainerHighFrequency::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::RSUContainerHighFrequency::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::RSUContainerHighFrequency::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.h new file mode 100644 index 00000000000..2e0adb94d29 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.h @@ -0,0 +1,237 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file RSUContainerHighFrequency.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RSUCONTAINERHIGHFREQUENCY_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RSUCONTAINERHIGHFREQUENCY_H_ + +#include "ProtectedCommunicationZonesRSU.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(RSUContainerHighFrequency_SOURCE) +#define RSUContainerHighFrequency_DllAPI __declspec( dllexport ) +#else +#define RSUContainerHighFrequency_DllAPI __declspec( dllimport ) +#endif // RSUContainerHighFrequency_SOURCE +#else +#define RSUContainerHighFrequency_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define RSUContainerHighFrequency_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure RSUContainerHighFrequency defined by the user in the IDL file. + * @ingroup RSUCONTAINERHIGHFREQUENCY + */ + class RSUContainerHighFrequency + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport RSUContainerHighFrequency(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~RSUContainerHighFrequency(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::RSUContainerHighFrequency that will be copied. + */ + eProsima_user_DllExport RSUContainerHighFrequency( + const RSUContainerHighFrequency& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::RSUContainerHighFrequency that will be copied. + */ + eProsima_user_DllExport RSUContainerHighFrequency( + RSUContainerHighFrequency&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::RSUContainerHighFrequency that will be copied. + */ + eProsima_user_DllExport RSUContainerHighFrequency& operator =( + const RSUContainerHighFrequency& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::RSUContainerHighFrequency that will be copied. + */ + eProsima_user_DllExport RSUContainerHighFrequency& operator =( + RSUContainerHighFrequency&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::RSUContainerHighFrequency object to compare. + */ + eProsima_user_DllExport bool operator ==( + const RSUContainerHighFrequency& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::RSUContainerHighFrequency object to compare. + */ + eProsima_user_DllExport bool operator !=( + const RSUContainerHighFrequency& x) const; + + /*! + * @brief This function copies the value in member protected_communication_zones_rsu + * @param _protected_communication_zones_rsu New value to be copied in member protected_communication_zones_rsu + */ + eProsima_user_DllExport void protected_communication_zones_rsu( + const etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU& _protected_communication_zones_rsu); + + /*! + * @brief This function moves the value in member protected_communication_zones_rsu + * @param _protected_communication_zones_rsu New value to be moved in member protected_communication_zones_rsu + */ + eProsima_user_DllExport void protected_communication_zones_rsu( + etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU&& _protected_communication_zones_rsu); + + /*! + * @brief This function returns a constant reference to member protected_communication_zones_rsu + * @return Constant reference to member protected_communication_zones_rsu + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU& protected_communication_zones_rsu() const; + + /*! + * @brief This function returns a reference to member protected_communication_zones_rsu + * @return Reference to member protected_communication_zones_rsu + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU& protected_communication_zones_rsu(); + /*! + * @brief This function sets a value in member protected_communication_zones_rsu_is_present + * @param _protected_communication_zones_rsu_is_present New value for member protected_communication_zones_rsu_is_present + */ + eProsima_user_DllExport void protected_communication_zones_rsu_is_present( + bool _protected_communication_zones_rsu_is_present); + + /*! + * @brief This function returns the value of member protected_communication_zones_rsu_is_present + * @return Value of member protected_communication_zones_rsu_is_present + */ + eProsima_user_DllExport bool protected_communication_zones_rsu_is_present() const; + + /*! + * @brief This function returns a reference to member protected_communication_zones_rsu_is_present + * @return Reference to member protected_communication_zones_rsu_is_present + */ + eProsima_user_DllExport bool& protected_communication_zones_rsu_is_present(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::RSUContainerHighFrequency& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU m_protected_communication_zones_rsu; + bool m_protected_communication_zones_rsu_is_present; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RSUCONTAINERHIGHFREQUENCY_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequencyPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequencyPubSubTypes.cxx new file mode 100644 index 00000000000..5afca4c53d8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequencyPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file RSUContainerHighFrequencyPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "RSUContainerHighFrequencyPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + RSUContainerHighFrequencyPubSubType::RSUContainerHighFrequencyPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::RSUContainerHighFrequency_"); + auto type_size = RSUContainerHighFrequency::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = RSUContainerHighFrequency::isKeyDefined(); + size_t keyLength = RSUContainerHighFrequency::getKeyMaxCdrSerializedSize() > 16 ? + RSUContainerHighFrequency::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + RSUContainerHighFrequencyPubSubType::~RSUContainerHighFrequencyPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool RSUContainerHighFrequencyPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + RSUContainerHighFrequency* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool RSUContainerHighFrequencyPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + RSUContainerHighFrequency* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function RSUContainerHighFrequencyPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* RSUContainerHighFrequencyPubSubType::createData() + { + return reinterpret_cast(new RSUContainerHighFrequency()); + } + + void RSUContainerHighFrequencyPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool RSUContainerHighFrequencyPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + RSUContainerHighFrequency* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + RSUContainerHighFrequency::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || RSUContainerHighFrequency::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequencyPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequencyPubSubTypes.h new file mode 100644 index 00000000000..14b111fc515 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequencyPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file RSUContainerHighFrequencyPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RSUCONTAINERHIGHFREQUENCY_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RSUCONTAINERHIGHFREQUENCY_PUBSUBTYPES_H_ + +#include +#include + +#include "RSUContainerHighFrequency.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated RSUContainerHighFrequency is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type RSUContainerHighFrequency defined by the user in the IDL file. + * @ingroup RSUCONTAINERHIGHFREQUENCY + */ + class RSUContainerHighFrequencyPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef RSUContainerHighFrequency type; + + eProsima_user_DllExport RSUContainerHighFrequencyPubSubType(); + + eProsima_user_DllExport virtual ~RSUContainerHighFrequencyPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RSUCONTAINERHIGHFREQUENCY_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePosition.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePosition.cxx new file mode 100644 index 00000000000..1529379e6ea --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePosition.cxx @@ -0,0 +1,334 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ReferencePosition.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "ReferencePosition.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::ReferencePosition::ReferencePosition() +{ + // m_latitude com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@58399d82 + + // m_longitude com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@26f96b85 + + // m_position_confidence_ellipse com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@46d8f407 + + // m_altitude com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@3c0036b + + +} + +etsi_its_cam_msgs::msg::ReferencePosition::~ReferencePosition() +{ + + + +} + +etsi_its_cam_msgs::msg::ReferencePosition::ReferencePosition( + const ReferencePosition& x) +{ + m_latitude = x.m_latitude; + m_longitude = x.m_longitude; + m_position_confidence_ellipse = x.m_position_confidence_ellipse; + m_altitude = x.m_altitude; +} + +etsi_its_cam_msgs::msg::ReferencePosition::ReferencePosition( + ReferencePosition&& x) +{ + m_latitude = std::move(x.m_latitude); + m_longitude = std::move(x.m_longitude); + m_position_confidence_ellipse = std::move(x.m_position_confidence_ellipse); + m_altitude = std::move(x.m_altitude); +} + +etsi_its_cam_msgs::msg::ReferencePosition& etsi_its_cam_msgs::msg::ReferencePosition::operator =( + const ReferencePosition& x) +{ + + m_latitude = x.m_latitude; + m_longitude = x.m_longitude; + m_position_confidence_ellipse = x.m_position_confidence_ellipse; + m_altitude = x.m_altitude; + + return *this; +} + +etsi_its_cam_msgs::msg::ReferencePosition& etsi_its_cam_msgs::msg::ReferencePosition::operator =( + ReferencePosition&& x) +{ + + m_latitude = std::move(x.m_latitude); + m_longitude = std::move(x.m_longitude); + m_position_confidence_ellipse = std::move(x.m_position_confidence_ellipse); + m_altitude = std::move(x.m_altitude); + + return *this; +} + +bool etsi_its_cam_msgs::msg::ReferencePosition::operator ==( + const ReferencePosition& x) const +{ + + return (m_latitude == x.m_latitude && m_longitude == x.m_longitude && m_position_confidence_ellipse == x.m_position_confidence_ellipse && m_altitude == x.m_altitude); +} + +bool etsi_its_cam_msgs::msg::ReferencePosition::operator !=( + const ReferencePosition& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::ReferencePosition::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::Latitude::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::Longitude::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::PosConfidenceEllipse::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::Altitude::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::ReferencePosition::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::ReferencePosition& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::Latitude::getCdrSerializedSize(data.latitude(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::Longitude::getCdrSerializedSize(data.longitude(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::PosConfidenceEllipse::getCdrSerializedSize(data.position_confidence_ellipse(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::Altitude::getCdrSerializedSize(data.altitude(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::ReferencePosition::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_latitude; + scdr << m_longitude; + scdr << m_position_confidence_ellipse; + scdr << m_altitude; + +} + +void etsi_its_cam_msgs::msg::ReferencePosition::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_latitude; + dcdr >> m_longitude; + dcdr >> m_position_confidence_ellipse; + dcdr >> m_altitude; +} + +/*! + * @brief This function copies the value in member latitude_ + * @param _latitude New value to be copied in member latitude_ + */ +void etsi_its_cam_msgs::msg::ReferencePosition::latitude( + const etsi_its_cam_msgs::msg::Latitude& _latitude) +{ + m_latitude = _latitude; +} + +/*! + * @brief This function moves the value in member latitude_ + * @param _latitude New value to be moved in member latitude_ + */ +void etsi_its_cam_msgs::msg::ReferencePosition::latitude( + etsi_its_cam_msgs::msg::Latitude&& _latitude) +{ + m_latitude = std::move(_latitude); +} + +/*! + * @brief This function returns a constant reference to member latitude_ + * @return Constant reference to member latitude_ + */ +const etsi_its_cam_msgs::msg::Latitude& etsi_its_cam_msgs::msg::ReferencePosition::latitude() const +{ + return m_latitude; +} + +/*! + * @brief This function returns a reference to member latitude_ + * @return Reference to member latitude_ + */ +etsi_its_cam_msgs::msg::Latitude& etsi_its_cam_msgs::msg::ReferencePosition::latitude() +{ + return m_latitude; +} +/*! + * @brief This function copies the value in member longitude_ + * @param _longitude New value to be copied in member longitude_ + */ +void etsi_its_cam_msgs::msg::ReferencePosition::longitude( + const etsi_its_cam_msgs::msg::Longitude& _longitude) +{ + m_longitude = _longitude; +} + +/*! + * @brief This function moves the value in member longitude_ + * @param _longitude New value to be moved in member longitude_ + */ +void etsi_its_cam_msgs::msg::ReferencePosition::longitude( + etsi_its_cam_msgs::msg::Longitude&& _longitude) +{ + m_longitude = std::move(_longitude); +} + +/*! + * @brief This function returns a constant reference to member longitude_ + * @return Constant reference to member longitude_ + */ +const etsi_its_cam_msgs::msg::Longitude& etsi_its_cam_msgs::msg::ReferencePosition::longitude() const +{ + return m_longitude; +} + +/*! + * @brief This function returns a reference to member longitude_ + * @return Reference to member longitude_ + */ +etsi_its_cam_msgs::msg::Longitude& etsi_its_cam_msgs::msg::ReferencePosition::longitude() +{ + return m_longitude; +} +/*! + * @brief This function copies the value in member position_confidence_ellipse + * @param _position_confidence_ellipse New value to be copied in member position_confidence_ellipse + */ +void etsi_its_cam_msgs::msg::ReferencePosition::position_confidence_ellipse( + const etsi_its_cam_msgs::msg::PosConfidenceEllipse& _position_confidence_ellipse) +{ + m_position_confidence_ellipse = _position_confidence_ellipse; +} + +/*! + * @brief This function moves the value in member position_confidence_ellipse + * @param _position_confidence_ellipse New value to be moved in member position_confidence_ellipse + */ +void etsi_its_cam_msgs::msg::ReferencePosition::position_confidence_ellipse( + etsi_its_cam_msgs::msg::PosConfidenceEllipse&& _position_confidence_ellipse) +{ + m_position_confidence_ellipse = std::move(_position_confidence_ellipse); +} + +/*! + * @brief This function returns a constant reference to member position_confidence_ellipse + * @return Constant reference to member position_confidence_ellipse + */ +const etsi_its_cam_msgs::msg::PosConfidenceEllipse& etsi_its_cam_msgs::msg::ReferencePosition::position_confidence_ellipse() const +{ + return m_position_confidence_ellipse; +} + +/*! + * @brief This function returns a reference to member position_confidence_ellipse + * @return Reference to member position_confidence_ellipse + */ +etsi_its_cam_msgs::msg::PosConfidenceEllipse& etsi_its_cam_msgs::msg::ReferencePosition::position_confidence_ellipse() +{ + return m_position_confidence_ellipse; +} +/*! + * @brief This function copies the value in member altitude_ + * @param _altitude New value to be copied in member altitude_ + */ +void etsi_its_cam_msgs::msg::ReferencePosition::altitude( + const etsi_its_cam_msgs::msg::Altitude& _altitude) +{ + m_altitude = _altitude; +} + +/*! + * @brief This function moves the value in member altitude_ + * @param _altitude New value to be moved in member altitude_ + */ +void etsi_its_cam_msgs::msg::ReferencePosition::altitude( + etsi_its_cam_msgs::msg::Altitude&& _altitude) +{ + m_altitude = std::move(_altitude); +} + +/*! + * @brief This function returns a constant reference to member altitude_ + * @return Constant reference to member altitude_ + */ +const etsi_its_cam_msgs::msg::Altitude& etsi_its_cam_msgs::msg::ReferencePosition::altitude() const +{ + return m_altitude; +} + +/*! + * @brief This function returns a reference to member altitude_ + * @return Reference to member altitude_ + */ +etsi_its_cam_msgs::msg::Altitude& etsi_its_cam_msgs::msg::ReferencePosition::altitude() +{ + return m_altitude; +} + +size_t etsi_its_cam_msgs::msg::ReferencePosition::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::ReferencePosition::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::ReferencePosition::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePosition.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePosition.h new file mode 100644 index 00000000000..1f450e3ffad --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePosition.h @@ -0,0 +1,298 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ReferencePosition.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_REFERENCEPOSITION_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_REFERENCEPOSITION_H_ + +#include "Latitude.h" +#include "PosConfidenceEllipse.h" +#include "Longitude.h" +#include "Altitude.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(ReferencePosition_SOURCE) +#define ReferencePosition_DllAPI __declspec( dllexport ) +#else +#define ReferencePosition_DllAPI __declspec( dllimport ) +#endif // ReferencePosition_SOURCE +#else +#define ReferencePosition_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define ReferencePosition_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure ReferencePosition defined by the user in the IDL file. + * @ingroup REFERENCEPOSITION + */ + class ReferencePosition + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport ReferencePosition(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~ReferencePosition(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::ReferencePosition that will be copied. + */ + eProsima_user_DllExport ReferencePosition( + const ReferencePosition& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::ReferencePosition that will be copied. + */ + eProsima_user_DllExport ReferencePosition( + ReferencePosition&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::ReferencePosition that will be copied. + */ + eProsima_user_DllExport ReferencePosition& operator =( + const ReferencePosition& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::ReferencePosition that will be copied. + */ + eProsima_user_DllExport ReferencePosition& operator =( + ReferencePosition&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::ReferencePosition object to compare. + */ + eProsima_user_DllExport bool operator ==( + const ReferencePosition& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::ReferencePosition object to compare. + */ + eProsima_user_DllExport bool operator !=( + const ReferencePosition& x) const; + + /*! + * @brief This function copies the value in member latitude_ + * @param _latitude New value to be copied in member latitude_ + */ + eProsima_user_DllExport void latitude( + const etsi_its_cam_msgs::msg::Latitude& _latitude); + + /*! + * @brief This function moves the value in member latitude_ + * @param _latitude New value to be moved in member latitude_ + */ + eProsima_user_DllExport void latitude( + etsi_its_cam_msgs::msg::Latitude&& _latitude); + + /*! + * @brief This function returns a constant reference to member latitude_ + * @return Constant reference to member latitude_ + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::Latitude& latitude() const; + + /*! + * @brief This function returns a reference to member latitude_ + * @return Reference to member latitude_ + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::Latitude& latitude(); + /*! + * @brief This function copies the value in member longitude_ + * @param _longitude New value to be copied in member longitude_ + */ + eProsima_user_DllExport void longitude( + const etsi_its_cam_msgs::msg::Longitude& _longitude); + + /*! + * @brief This function moves the value in member longitude_ + * @param _longitude New value to be moved in member longitude_ + */ + eProsima_user_DllExport void longitude( + etsi_its_cam_msgs::msg::Longitude&& _longitude); + + /*! + * @brief This function returns a constant reference to member longitude_ + * @return Constant reference to member longitude_ + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::Longitude& longitude() const; + + /*! + * @brief This function returns a reference to member longitude_ + * @return Reference to member longitude_ + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::Longitude& longitude(); + /*! + * @brief This function copies the value in member position_confidence_ellipse + * @param _position_confidence_ellipse New value to be copied in member position_confidence_ellipse + */ + eProsima_user_DllExport void position_confidence_ellipse( + const etsi_its_cam_msgs::msg::PosConfidenceEllipse& _position_confidence_ellipse); + + /*! + * @brief This function moves the value in member position_confidence_ellipse + * @param _position_confidence_ellipse New value to be moved in member position_confidence_ellipse + */ + eProsima_user_DllExport void position_confidence_ellipse( + etsi_its_cam_msgs::msg::PosConfidenceEllipse&& _position_confidence_ellipse); + + /*! + * @brief This function returns a constant reference to member position_confidence_ellipse + * @return Constant reference to member position_confidence_ellipse + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::PosConfidenceEllipse& position_confidence_ellipse() const; + + /*! + * @brief This function returns a reference to member position_confidence_ellipse + * @return Reference to member position_confidence_ellipse + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::PosConfidenceEllipse& position_confidence_ellipse(); + /*! + * @brief This function copies the value in member altitude_ + * @param _altitude New value to be copied in member altitude_ + */ + eProsima_user_DllExport void altitude( + const etsi_its_cam_msgs::msg::Altitude& _altitude); + + /*! + * @brief This function moves the value in member altitude_ + * @param _altitude New value to be moved in member altitude_ + */ + eProsima_user_DllExport void altitude( + etsi_its_cam_msgs::msg::Altitude&& _altitude); + + /*! + * @brief This function returns a constant reference to member altitude_ + * @return Constant reference to member altitude_ + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::Altitude& altitude() const; + + /*! + * @brief This function returns a reference to member altitude_ + * @return Reference to member altitude_ + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::Altitude& altitude(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::ReferencePosition& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::Latitude m_latitude; + etsi_its_cam_msgs::msg::Longitude m_longitude; + etsi_its_cam_msgs::msg::PosConfidenceEllipse m_position_confidence_ellipse; + etsi_its_cam_msgs::msg::Altitude m_altitude; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_REFERENCEPOSITION_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePositionPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePositionPubSubTypes.cxx new file mode 100644 index 00000000000..7f1c30af0d2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePositionPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ReferencePositionPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "ReferencePositionPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + ReferencePositionPubSubType::ReferencePositionPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::ReferencePosition_"); + auto type_size = ReferencePosition::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = ReferencePosition::isKeyDefined(); + size_t keyLength = ReferencePosition::getKeyMaxCdrSerializedSize() > 16 ? + ReferencePosition::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + ReferencePositionPubSubType::~ReferencePositionPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool ReferencePositionPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + ReferencePosition* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool ReferencePositionPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + ReferencePosition* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function ReferencePositionPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* ReferencePositionPubSubType::createData() + { + return reinterpret_cast(new ReferencePosition()); + } + + void ReferencePositionPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool ReferencePositionPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + ReferencePosition* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + ReferencePosition::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || ReferencePosition::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePositionPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePositionPubSubTypes.h new file mode 100644 index 00000000000..c837c3ebe9e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePositionPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ReferencePositionPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_REFERENCEPOSITION_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_REFERENCEPOSITION_PUBSUBTYPES_H_ + +#include +#include + +#include "ReferencePosition.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated ReferencePosition is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type ReferencePosition defined by the user in the IDL file. + * @ingroup REFERENCEPOSITION + */ + class ReferencePositionPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef ReferencePosition type; + + eProsima_user_DllExport ReferencePositionPubSubType(); + + eProsima_user_DllExport virtual ~ReferencePositionPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) ReferencePosition(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_REFERENCEPOSITION_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainer.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainer.cxx new file mode 100644 index 00000000000..e1a6fdf3763 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainer.cxx @@ -0,0 +1,190 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file RescueContainer.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "RescueContainer.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::RescueContainer::RescueContainer() +{ + // m_light_bar_siren_in_use com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@1bdf8190 + + +} + +etsi_its_cam_msgs::msg::RescueContainer::~RescueContainer() +{ +} + +etsi_its_cam_msgs::msg::RescueContainer::RescueContainer( + const RescueContainer& x) +{ + m_light_bar_siren_in_use = x.m_light_bar_siren_in_use; +} + +etsi_its_cam_msgs::msg::RescueContainer::RescueContainer( + RescueContainer&& x) +{ + m_light_bar_siren_in_use = std::move(x.m_light_bar_siren_in_use); +} + +etsi_its_cam_msgs::msg::RescueContainer& etsi_its_cam_msgs::msg::RescueContainer::operator =( + const RescueContainer& x) +{ + + m_light_bar_siren_in_use = x.m_light_bar_siren_in_use; + + return *this; +} + +etsi_its_cam_msgs::msg::RescueContainer& etsi_its_cam_msgs::msg::RescueContainer::operator =( + RescueContainer&& x) +{ + + m_light_bar_siren_in_use = std::move(x.m_light_bar_siren_in_use); + + return *this; +} + +bool etsi_its_cam_msgs::msg::RescueContainer::operator ==( + const RescueContainer& x) const +{ + + return (m_light_bar_siren_in_use == x.m_light_bar_siren_in_use); +} + +bool etsi_its_cam_msgs::msg::RescueContainer::operator !=( + const RescueContainer& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::RescueContainer::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::LightBarSirenInUse::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::RescueContainer::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::RescueContainer& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::LightBarSirenInUse::getCdrSerializedSize(data.light_bar_siren_in_use(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::RescueContainer::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_light_bar_siren_in_use; + +} + +void etsi_its_cam_msgs::msg::RescueContainer::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_light_bar_siren_in_use; +} + +/*! + * @brief This function copies the value in member light_bar_siren_in_use + * @param _light_bar_siren_in_use New value to be copied in member light_bar_siren_in_use + */ +void etsi_its_cam_msgs::msg::RescueContainer::light_bar_siren_in_use( + const etsi_its_cam_msgs::msg::LightBarSirenInUse& _light_bar_siren_in_use) +{ + m_light_bar_siren_in_use = _light_bar_siren_in_use; +} + +/*! + * @brief This function moves the value in member light_bar_siren_in_use + * @param _light_bar_siren_in_use New value to be moved in member light_bar_siren_in_use + */ +void etsi_its_cam_msgs::msg::RescueContainer::light_bar_siren_in_use( + etsi_its_cam_msgs::msg::LightBarSirenInUse&& _light_bar_siren_in_use) +{ + m_light_bar_siren_in_use = std::move(_light_bar_siren_in_use); +} + +/*! + * @brief This function returns a constant reference to member light_bar_siren_in_use + * @return Constant reference to member light_bar_siren_in_use + */ +const etsi_its_cam_msgs::msg::LightBarSirenInUse& etsi_its_cam_msgs::msg::RescueContainer::light_bar_siren_in_use() const +{ + return m_light_bar_siren_in_use; +} + +/*! + * @brief This function returns a reference to member light_bar_siren_in_use + * @return Reference to member light_bar_siren_in_use + */ +etsi_its_cam_msgs::msg::LightBarSirenInUse& etsi_its_cam_msgs::msg::RescueContainer::light_bar_siren_in_use() +{ + return m_light_bar_siren_in_use; +} + +size_t etsi_its_cam_msgs::msg::RescueContainer::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::RescueContainer::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::RescueContainer::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainer.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainer.h new file mode 100644 index 00000000000..a2816e37c46 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainer.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file RescueContainer.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RESCUECONTAINER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RESCUECONTAINER_H_ + +#include "LightBarSirenInUse.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(RescueContainer_SOURCE) +#define RescueContainer_DllAPI __declspec( dllexport ) +#else +#define RescueContainer_DllAPI __declspec( dllimport ) +#endif // RescueContainer_SOURCE +#else +#define RescueContainer_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define RescueContainer_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure RescueContainer defined by the user in the IDL file. + * @ingroup RESCUECONTAINER + */ + class RescueContainer + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport RescueContainer(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~RescueContainer(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::RescueContainer that will be copied. + */ + eProsima_user_DllExport RescueContainer( + const RescueContainer& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::RescueContainer that will be copied. + */ + eProsima_user_DllExport RescueContainer( + RescueContainer&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::RescueContainer that will be copied. + */ + eProsima_user_DllExport RescueContainer& operator =( + const RescueContainer& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::RescueContainer that will be copied. + */ + eProsima_user_DllExport RescueContainer& operator =( + RescueContainer&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::RescueContainer object to compare. + */ + eProsima_user_DllExport bool operator ==( + const RescueContainer& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::RescueContainer object to compare. + */ + eProsima_user_DllExport bool operator !=( + const RescueContainer& x) const; + + /*! + * @brief This function copies the value in member light_bar_siren_in_use + * @param _light_bar_siren_in_use New value to be copied in member light_bar_siren_in_use + */ + eProsima_user_DllExport void light_bar_siren_in_use( + const etsi_its_cam_msgs::msg::LightBarSirenInUse& _light_bar_siren_in_use); + + /*! + * @brief This function moves the value in member light_bar_siren_in_use + * @param _light_bar_siren_in_use New value to be moved in member light_bar_siren_in_use + */ + eProsima_user_DllExport void light_bar_siren_in_use( + etsi_its_cam_msgs::msg::LightBarSirenInUse&& _light_bar_siren_in_use); + + /*! + * @brief This function returns a constant reference to member light_bar_siren_in_use + * @return Constant reference to member light_bar_siren_in_use + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::LightBarSirenInUse& light_bar_siren_in_use() const; + + /*! + * @brief This function returns a reference to member light_bar_siren_in_use + * @return Reference to member light_bar_siren_in_use + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::LightBarSirenInUse& light_bar_siren_in_use(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::RescueContainer& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::LightBarSirenInUse m_light_bar_siren_in_use; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RESCUECONTAINER_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainerPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainerPubSubTypes.cxx new file mode 100644 index 00000000000..5b2b7e13557 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainerPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file RescueContainerPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "RescueContainerPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + RescueContainerPubSubType::RescueContainerPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::RescueContainer_"); + auto type_size = RescueContainer::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = RescueContainer::isKeyDefined(); + size_t keyLength = RescueContainer::getKeyMaxCdrSerializedSize() > 16 ? + RescueContainer::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + RescueContainerPubSubType::~RescueContainerPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool RescueContainerPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + RescueContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool RescueContainerPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + RescueContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function RescueContainerPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* RescueContainerPubSubType::createData() + { + return reinterpret_cast(new RescueContainer()); + } + + void RescueContainerPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool RescueContainerPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + RescueContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + RescueContainer::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || RescueContainer::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainerPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainerPubSubTypes.h new file mode 100644 index 00000000000..fbd93064c10 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainerPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file RescueContainerPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RESCUECONTAINER_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RESCUECONTAINER_PUBSUBTYPES_H_ + +#include +#include + +#include "RescueContainer.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated RescueContainer is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type RescueContainer defined by the user in the IDL file. + * @ingroup RESCUECONTAINER + */ + class RescueContainerPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef RescueContainer type; + + eProsima_user_DllExport RescueContainerPubSubType(); + + eProsima_user_DllExport virtual ~RescueContainerPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RESCUECONTAINER_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.cxx new file mode 100644 index 00000000000..19aa9fdc442 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.cxx @@ -0,0 +1,372 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file RoadWorksContainerBasic.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "RoadWorksContainerBasic.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::RoadWorksContainerBasic::RoadWorksContainerBasic() +{ + // m_roadworks_sub_cause_code com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@6ffab045 + + // m_roadworks_sub_cause_code_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@26fb628 + m_roadworks_sub_cause_code_is_present = false; + // m_light_bar_siren_in_use com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@3e2943ab + + // m_closed_lanes com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@70dd7e15 + + // m_closed_lanes_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@4a9f80d3 + m_closed_lanes_is_present = false; + +} + +etsi_its_cam_msgs::msg::RoadWorksContainerBasic::~RoadWorksContainerBasic() +{ + + + + +} + +etsi_its_cam_msgs::msg::RoadWorksContainerBasic::RoadWorksContainerBasic( + const RoadWorksContainerBasic& x) +{ + m_roadworks_sub_cause_code = x.m_roadworks_sub_cause_code; + m_roadworks_sub_cause_code_is_present = x.m_roadworks_sub_cause_code_is_present; + m_light_bar_siren_in_use = x.m_light_bar_siren_in_use; + m_closed_lanes = x.m_closed_lanes; + m_closed_lanes_is_present = x.m_closed_lanes_is_present; +} + +etsi_its_cam_msgs::msg::RoadWorksContainerBasic::RoadWorksContainerBasic( + RoadWorksContainerBasic&& x) +{ + m_roadworks_sub_cause_code = std::move(x.m_roadworks_sub_cause_code); + m_roadworks_sub_cause_code_is_present = x.m_roadworks_sub_cause_code_is_present; + m_light_bar_siren_in_use = std::move(x.m_light_bar_siren_in_use); + m_closed_lanes = std::move(x.m_closed_lanes); + m_closed_lanes_is_present = x.m_closed_lanes_is_present; +} + +etsi_its_cam_msgs::msg::RoadWorksContainerBasic& etsi_its_cam_msgs::msg::RoadWorksContainerBasic::operator =( + const RoadWorksContainerBasic& x) +{ + + m_roadworks_sub_cause_code = x.m_roadworks_sub_cause_code; + m_roadworks_sub_cause_code_is_present = x.m_roadworks_sub_cause_code_is_present; + m_light_bar_siren_in_use = x.m_light_bar_siren_in_use; + m_closed_lanes = x.m_closed_lanes; + m_closed_lanes_is_present = x.m_closed_lanes_is_present; + + return *this; +} + +etsi_its_cam_msgs::msg::RoadWorksContainerBasic& etsi_its_cam_msgs::msg::RoadWorksContainerBasic::operator =( + RoadWorksContainerBasic&& x) +{ + + m_roadworks_sub_cause_code = std::move(x.m_roadworks_sub_cause_code); + m_roadworks_sub_cause_code_is_present = x.m_roadworks_sub_cause_code_is_present; + m_light_bar_siren_in_use = std::move(x.m_light_bar_siren_in_use); + m_closed_lanes = std::move(x.m_closed_lanes); + m_closed_lanes_is_present = x.m_closed_lanes_is_present; + + return *this; +} + +bool etsi_its_cam_msgs::msg::RoadWorksContainerBasic::operator ==( + const RoadWorksContainerBasic& x) const +{ + + return (m_roadworks_sub_cause_code == x.m_roadworks_sub_cause_code && m_roadworks_sub_cause_code_is_present == x.m_roadworks_sub_cause_code_is_present && m_light_bar_siren_in_use == x.m_light_bar_siren_in_use && m_closed_lanes == x.m_closed_lanes && m_closed_lanes_is_present == x.m_closed_lanes_is_present); +} + +bool etsi_its_cam_msgs::msg::RoadWorksContainerBasic::operator !=( + const RoadWorksContainerBasic& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::RoadWorksContainerBasic::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::RoadworksSubCauseCode::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::LightBarSirenInUse::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::ClosedLanes::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::RoadWorksContainerBasic::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::RoadWorksContainerBasic& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::RoadworksSubCauseCode::getCdrSerializedSize(data.roadworks_sub_cause_code(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::LightBarSirenInUse::getCdrSerializedSize(data.light_bar_siren_in_use(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::ClosedLanes::getCdrSerializedSize(data.closed_lanes(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::RoadWorksContainerBasic::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_roadworks_sub_cause_code; + scdr << m_roadworks_sub_cause_code_is_present; + scdr << m_light_bar_siren_in_use; + scdr << m_closed_lanes; + scdr << m_closed_lanes_is_present; + +} + +void etsi_its_cam_msgs::msg::RoadWorksContainerBasic::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_roadworks_sub_cause_code; + dcdr >> m_roadworks_sub_cause_code_is_present; + dcdr >> m_light_bar_siren_in_use; + dcdr >> m_closed_lanes; + dcdr >> m_closed_lanes_is_present; +} + +/*! + * @brief This function copies the value in member roadworks_sub_cause_code + * @param _roadworks_sub_cause_code New value to be copied in member roadworks_sub_cause_code + */ +void etsi_its_cam_msgs::msg::RoadWorksContainerBasic::roadworks_sub_cause_code( + const etsi_its_cam_msgs::msg::RoadworksSubCauseCode& _roadworks_sub_cause_code) +{ + m_roadworks_sub_cause_code = _roadworks_sub_cause_code; +} + +/*! + * @brief This function moves the value in member roadworks_sub_cause_code + * @param _roadworks_sub_cause_code New value to be moved in member roadworks_sub_cause_code + */ +void etsi_its_cam_msgs::msg::RoadWorksContainerBasic::roadworks_sub_cause_code( + etsi_its_cam_msgs::msg::RoadworksSubCauseCode&& _roadworks_sub_cause_code) +{ + m_roadworks_sub_cause_code = std::move(_roadworks_sub_cause_code); +} + +/*! + * @brief This function returns a constant reference to member roadworks_sub_cause_code + * @return Constant reference to member roadworks_sub_cause_code + */ +const etsi_its_cam_msgs::msg::RoadworksSubCauseCode& etsi_its_cam_msgs::msg::RoadWorksContainerBasic::roadworks_sub_cause_code() const +{ + return m_roadworks_sub_cause_code; +} + +/*! + * @brief This function returns a reference to member roadworks_sub_cause_code + * @return Reference to member roadworks_sub_cause_code + */ +etsi_its_cam_msgs::msg::RoadworksSubCauseCode& etsi_its_cam_msgs::msg::RoadWorksContainerBasic::roadworks_sub_cause_code() +{ + return m_roadworks_sub_cause_code; +} +/*! + * @brief This function sets a value in member roadworks_sub_cause_code_is_present + * @param _roadworks_sub_cause_code_is_present New value for member roadworks_sub_cause_code_is_present + */ +void etsi_its_cam_msgs::msg::RoadWorksContainerBasic::roadworks_sub_cause_code_is_present( + bool _roadworks_sub_cause_code_is_present) +{ + m_roadworks_sub_cause_code_is_present = _roadworks_sub_cause_code_is_present; +} + +/*! + * @brief This function returns the value of member roadworks_sub_cause_code_is_present + * @return Value of member roadworks_sub_cause_code_is_present + */ +bool etsi_its_cam_msgs::msg::RoadWorksContainerBasic::roadworks_sub_cause_code_is_present() const +{ + return m_roadworks_sub_cause_code_is_present; +} + +/*! + * @brief This function returns a reference to member roadworks_sub_cause_code_is_present + * @return Reference to member roadworks_sub_cause_code_is_present + */ +bool& etsi_its_cam_msgs::msg::RoadWorksContainerBasic::roadworks_sub_cause_code_is_present() +{ + return m_roadworks_sub_cause_code_is_present; +} + +/*! + * @brief This function copies the value in member light_bar_siren_in_use + * @param _light_bar_siren_in_use New value to be copied in member light_bar_siren_in_use + */ +void etsi_its_cam_msgs::msg::RoadWorksContainerBasic::light_bar_siren_in_use( + const etsi_its_cam_msgs::msg::LightBarSirenInUse& _light_bar_siren_in_use) +{ + m_light_bar_siren_in_use = _light_bar_siren_in_use; +} + +/*! + * @brief This function moves the value in member light_bar_siren_in_use + * @param _light_bar_siren_in_use New value to be moved in member light_bar_siren_in_use + */ +void etsi_its_cam_msgs::msg::RoadWorksContainerBasic::light_bar_siren_in_use( + etsi_its_cam_msgs::msg::LightBarSirenInUse&& _light_bar_siren_in_use) +{ + m_light_bar_siren_in_use = std::move(_light_bar_siren_in_use); +} + +/*! + * @brief This function returns a constant reference to member light_bar_siren_in_use + * @return Constant reference to member light_bar_siren_in_use + */ +const etsi_its_cam_msgs::msg::LightBarSirenInUse& etsi_its_cam_msgs::msg::RoadWorksContainerBasic::light_bar_siren_in_use() const +{ + return m_light_bar_siren_in_use; +} + +/*! + * @brief This function returns a reference to member light_bar_siren_in_use + * @return Reference to member light_bar_siren_in_use + */ +etsi_its_cam_msgs::msg::LightBarSirenInUse& etsi_its_cam_msgs::msg::RoadWorksContainerBasic::light_bar_siren_in_use() +{ + return m_light_bar_siren_in_use; +} +/*! + * @brief This function copies the value in member closed_lanes + * @param _closed_lanes New value to be copied in member closed_lanes + */ +void etsi_its_cam_msgs::msg::RoadWorksContainerBasic::closed_lanes( + const etsi_its_cam_msgs::msg::ClosedLanes& _closed_lanes) +{ + m_closed_lanes = _closed_lanes; +} + +/*! + * @brief This function moves the value in member closed_lanes + * @param _closed_lanes New value to be moved in member closed_lanes + */ +void etsi_its_cam_msgs::msg::RoadWorksContainerBasic::closed_lanes( + etsi_its_cam_msgs::msg::ClosedLanes&& _closed_lanes) +{ + m_closed_lanes = std::move(_closed_lanes); +} + +/*! + * @brief This function returns a constant reference to member closed_lanes + * @return Constant reference to member closed_lanes + */ +const etsi_its_cam_msgs::msg::ClosedLanes& etsi_its_cam_msgs::msg::RoadWorksContainerBasic::closed_lanes() const +{ + return m_closed_lanes; +} + +/*! + * @brief This function returns a reference to member closed_lanes + * @return Reference to member closed_lanes + */ +etsi_its_cam_msgs::msg::ClosedLanes& etsi_its_cam_msgs::msg::RoadWorksContainerBasic::closed_lanes() +{ + return m_closed_lanes; +} +/*! + * @brief This function sets a value in member closed_lanes_is_present + * @param _closed_lanes_is_present New value for member closed_lanes_is_present + */ +void etsi_its_cam_msgs::msg::RoadWorksContainerBasic::closed_lanes_is_present( + bool _closed_lanes_is_present) +{ + m_closed_lanes_is_present = _closed_lanes_is_present; +} + +/*! + * @brief This function returns the value of member closed_lanes_is_present + * @return Value of member closed_lanes_is_present + */ +bool etsi_its_cam_msgs::msg::RoadWorksContainerBasic::closed_lanes_is_present() const +{ + return m_closed_lanes_is_present; +} + +/*! + * @brief This function returns a reference to member closed_lanes_is_present + * @return Reference to member closed_lanes_is_present + */ +bool& etsi_its_cam_msgs::msg::RoadWorksContainerBasic::closed_lanes_is_present() +{ + return m_closed_lanes_is_present; +} + + +size_t etsi_its_cam_msgs::msg::RoadWorksContainerBasic::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::RoadWorksContainerBasic::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::RoadWorksContainerBasic::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.h new file mode 100644 index 00000000000..146e9d7bfa6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.h @@ -0,0 +1,311 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file RoadWorksContainerBasic.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSCONTAINERBASIC_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSCONTAINERBASIC_H_ + +#include "RoadworksSubCauseCode.h" +#include "ClosedLanes.h" +#include "LightBarSirenInUse.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(RoadWorksContainerBasic_SOURCE) +#define RoadWorksContainerBasic_DllAPI __declspec( dllexport ) +#else +#define RoadWorksContainerBasic_DllAPI __declspec( dllimport ) +#endif // RoadWorksContainerBasic_SOURCE +#else +#define RoadWorksContainerBasic_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define RoadWorksContainerBasic_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure RoadWorksContainerBasic defined by the user in the IDL file. + * @ingroup ROADWORKSCONTAINERBASIC + */ + class RoadWorksContainerBasic + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport RoadWorksContainerBasic(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~RoadWorksContainerBasic(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::RoadWorksContainerBasic that will be copied. + */ + eProsima_user_DllExport RoadWorksContainerBasic( + const RoadWorksContainerBasic& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::RoadWorksContainerBasic that will be copied. + */ + eProsima_user_DllExport RoadWorksContainerBasic( + RoadWorksContainerBasic&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::RoadWorksContainerBasic that will be copied. + */ + eProsima_user_DllExport RoadWorksContainerBasic& operator =( + const RoadWorksContainerBasic& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::RoadWorksContainerBasic that will be copied. + */ + eProsima_user_DllExport RoadWorksContainerBasic& operator =( + RoadWorksContainerBasic&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::RoadWorksContainerBasic object to compare. + */ + eProsima_user_DllExport bool operator ==( + const RoadWorksContainerBasic& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::RoadWorksContainerBasic object to compare. + */ + eProsima_user_DllExport bool operator !=( + const RoadWorksContainerBasic& x) const; + + /*! + * @brief This function copies the value in member roadworks_sub_cause_code + * @param _roadworks_sub_cause_code New value to be copied in member roadworks_sub_cause_code + */ + eProsima_user_DllExport void roadworks_sub_cause_code( + const etsi_its_cam_msgs::msg::RoadworksSubCauseCode& _roadworks_sub_cause_code); + + /*! + * @brief This function moves the value in member roadworks_sub_cause_code + * @param _roadworks_sub_cause_code New value to be moved in member roadworks_sub_cause_code + */ + eProsima_user_DllExport void roadworks_sub_cause_code( + etsi_its_cam_msgs::msg::RoadworksSubCauseCode&& _roadworks_sub_cause_code); + + /*! + * @brief This function returns a constant reference to member roadworks_sub_cause_code + * @return Constant reference to member roadworks_sub_cause_code + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::RoadworksSubCauseCode& roadworks_sub_cause_code() const; + + /*! + * @brief This function returns a reference to member roadworks_sub_cause_code + * @return Reference to member roadworks_sub_cause_code + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::RoadworksSubCauseCode& roadworks_sub_cause_code(); + /*! + * @brief This function sets a value in member roadworks_sub_cause_code_is_present + * @param _roadworks_sub_cause_code_is_present New value for member roadworks_sub_cause_code_is_present + */ + eProsima_user_DllExport void roadworks_sub_cause_code_is_present( + bool _roadworks_sub_cause_code_is_present); + + /*! + * @brief This function returns the value of member roadworks_sub_cause_code_is_present + * @return Value of member roadworks_sub_cause_code_is_present + */ + eProsima_user_DllExport bool roadworks_sub_cause_code_is_present() const; + + /*! + * @brief This function returns a reference to member roadworks_sub_cause_code_is_present + * @return Reference to member roadworks_sub_cause_code_is_present + */ + eProsima_user_DllExport bool& roadworks_sub_cause_code_is_present(); + + /*! + * @brief This function copies the value in member light_bar_siren_in_use + * @param _light_bar_siren_in_use New value to be copied in member light_bar_siren_in_use + */ + eProsima_user_DllExport void light_bar_siren_in_use( + const etsi_its_cam_msgs::msg::LightBarSirenInUse& _light_bar_siren_in_use); + + /*! + * @brief This function moves the value in member light_bar_siren_in_use + * @param _light_bar_siren_in_use New value to be moved in member light_bar_siren_in_use + */ + eProsima_user_DllExport void light_bar_siren_in_use( + etsi_its_cam_msgs::msg::LightBarSirenInUse&& _light_bar_siren_in_use); + + /*! + * @brief This function returns a constant reference to member light_bar_siren_in_use + * @return Constant reference to member light_bar_siren_in_use + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::LightBarSirenInUse& light_bar_siren_in_use() const; + + /*! + * @brief This function returns a reference to member light_bar_siren_in_use + * @return Reference to member light_bar_siren_in_use + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::LightBarSirenInUse& light_bar_siren_in_use(); + /*! + * @brief This function copies the value in member closed_lanes + * @param _closed_lanes New value to be copied in member closed_lanes + */ + eProsima_user_DllExport void closed_lanes( + const etsi_its_cam_msgs::msg::ClosedLanes& _closed_lanes); + + /*! + * @brief This function moves the value in member closed_lanes + * @param _closed_lanes New value to be moved in member closed_lanes + */ + eProsima_user_DllExport void closed_lanes( + etsi_its_cam_msgs::msg::ClosedLanes&& _closed_lanes); + + /*! + * @brief This function returns a constant reference to member closed_lanes + * @return Constant reference to member closed_lanes + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::ClosedLanes& closed_lanes() const; + + /*! + * @brief This function returns a reference to member closed_lanes + * @return Reference to member closed_lanes + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::ClosedLanes& closed_lanes(); + /*! + * @brief This function sets a value in member closed_lanes_is_present + * @param _closed_lanes_is_present New value for member closed_lanes_is_present + */ + eProsima_user_DllExport void closed_lanes_is_present( + bool _closed_lanes_is_present); + + /*! + * @brief This function returns the value of member closed_lanes_is_present + * @return Value of member closed_lanes_is_present + */ + eProsima_user_DllExport bool closed_lanes_is_present() const; + + /*! + * @brief This function returns a reference to member closed_lanes_is_present + * @return Reference to member closed_lanes_is_present + */ + eProsima_user_DllExport bool& closed_lanes_is_present(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::RoadWorksContainerBasic& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::RoadworksSubCauseCode m_roadworks_sub_cause_code; + bool m_roadworks_sub_cause_code_is_present; + etsi_its_cam_msgs::msg::LightBarSirenInUse m_light_bar_siren_in_use; + etsi_its_cam_msgs::msg::ClosedLanes m_closed_lanes; + bool m_closed_lanes_is_present; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSCONTAINERBASIC_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasicPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasicPubSubTypes.cxx new file mode 100644 index 00000000000..7f28f1f3f06 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasicPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file RoadWorksContainerBasicPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "RoadWorksContainerBasicPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + RoadWorksContainerBasicPubSubType::RoadWorksContainerBasicPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::RoadWorksContainerBasic_"); + auto type_size = RoadWorksContainerBasic::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = RoadWorksContainerBasic::isKeyDefined(); + size_t keyLength = RoadWorksContainerBasic::getKeyMaxCdrSerializedSize() > 16 ? + RoadWorksContainerBasic::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + RoadWorksContainerBasicPubSubType::~RoadWorksContainerBasicPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool RoadWorksContainerBasicPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + RoadWorksContainerBasic* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool RoadWorksContainerBasicPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + RoadWorksContainerBasic* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function RoadWorksContainerBasicPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* RoadWorksContainerBasicPubSubType::createData() + { + return reinterpret_cast(new RoadWorksContainerBasic()); + } + + void RoadWorksContainerBasicPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool RoadWorksContainerBasicPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + RoadWorksContainerBasic* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + RoadWorksContainerBasic::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || RoadWorksContainerBasic::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasicPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasicPubSubTypes.h new file mode 100644 index 00000000000..ba8645908e9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasicPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file RoadWorksContainerBasicPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSCONTAINERBASIC_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSCONTAINERBASIC_PUBSUBTYPES_H_ + +#include +#include + +#include "RoadWorksContainerBasic.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated RoadWorksContainerBasic is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type RoadWorksContainerBasic defined by the user in the IDL file. + * @ingroup ROADWORKSCONTAINERBASIC + */ + class RoadWorksContainerBasicPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef RoadWorksContainerBasic type; + + eProsima_user_DllExport RoadWorksContainerBasicPubSubType(); + + eProsima_user_DllExport virtual ~RoadWorksContainerBasicPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSCONTAINERBASIC_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.cxx new file mode 100644 index 00000000000..27b98d6d0be --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.cxx @@ -0,0 +1,193 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file RoadworksSubCauseCode.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "RoadworksSubCauseCode.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + + + + +etsi_its_cam_msgs::msg::RoadworksSubCauseCode::RoadworksSubCauseCode() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@89ff02e + m_value = 0; + +} + +etsi_its_cam_msgs::msg::RoadworksSubCauseCode::~RoadworksSubCauseCode() +{ +} + +etsi_its_cam_msgs::msg::RoadworksSubCauseCode::RoadworksSubCauseCode( + const RoadworksSubCauseCode& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::RoadworksSubCauseCode::RoadworksSubCauseCode( + RoadworksSubCauseCode&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::RoadworksSubCauseCode& etsi_its_cam_msgs::msg::RoadworksSubCauseCode::operator =( + const RoadworksSubCauseCode& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::RoadworksSubCauseCode& etsi_its_cam_msgs::msg::RoadworksSubCauseCode::operator =( + RoadworksSubCauseCode&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::RoadworksSubCauseCode::operator ==( + const RoadworksSubCauseCode& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::RoadworksSubCauseCode::operator !=( + const RoadworksSubCauseCode& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::RoadworksSubCauseCode::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::RoadworksSubCauseCode::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::RoadworksSubCauseCode& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::RoadworksSubCauseCode::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::RoadworksSubCauseCode::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::RoadworksSubCauseCode::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::RoadworksSubCauseCode::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::RoadworksSubCauseCode::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::RoadworksSubCauseCode::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::RoadworksSubCauseCode::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::RoadworksSubCauseCode::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.h new file mode 100644 index 00000000000..b81fec0d395 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.h @@ -0,0 +1,221 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file RoadworksSubCauseCode.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSSUBCAUSECODE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSSUBCAUSECODE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(RoadworksSubCauseCode_SOURCE) +#define RoadworksSubCauseCode_DllAPI __declspec( dllexport ) +#else +#define RoadworksSubCauseCode_DllAPI __declspec( dllimport ) +#endif // RoadworksSubCauseCode_SOURCE +#else +#define RoadworksSubCauseCode_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define RoadworksSubCauseCode_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace RoadworksSubCauseCode_Constants { + const uint8_t MIN = 0; + const uint8_t MAX = 255; + const uint8_t UNAVAILABLE = 0; + const uint8_t MAJOR_ROADWORKS = 1; + const uint8_t ROAD_MARKING_WORK = 2; + const uint8_t SLOW_MOVING_ROAD_MAINTENANCE = 3; + const uint8_t SHORT_TERM_STATIONARY_ROADWORKS = 4; + const uint8_t STREET_CLEANING = 5; + const uint8_t WINTER_SERVICE = 6; + } // namespace RoadworksSubCauseCode_Constants + /*! + * @brief This class represents the structure RoadworksSubCauseCode defined by the user in the IDL file. + * @ingroup ROADWORKSSUBCAUSECODE + */ + class RoadworksSubCauseCode + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport RoadworksSubCauseCode(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~RoadworksSubCauseCode(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::RoadworksSubCauseCode that will be copied. + */ + eProsima_user_DllExport RoadworksSubCauseCode( + const RoadworksSubCauseCode& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::RoadworksSubCauseCode that will be copied. + */ + eProsima_user_DllExport RoadworksSubCauseCode( + RoadworksSubCauseCode&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::RoadworksSubCauseCode that will be copied. + */ + eProsima_user_DllExport RoadworksSubCauseCode& operator =( + const RoadworksSubCauseCode& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::RoadworksSubCauseCode that will be copied. + */ + eProsima_user_DllExport RoadworksSubCauseCode& operator =( + RoadworksSubCauseCode&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::RoadworksSubCauseCode object to compare. + */ + eProsima_user_DllExport bool operator ==( + const RoadworksSubCauseCode& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::RoadworksSubCauseCode object to compare. + */ + eProsima_user_DllExport bool operator !=( + const RoadworksSubCauseCode& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::RoadworksSubCauseCode& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSSUBCAUSECODE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCodePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCodePubSubTypes.cxx new file mode 100644 index 00000000000..58926c36eab --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCodePubSubTypes.cxx @@ -0,0 +1,188 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file RoadworksSubCauseCodePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "RoadworksSubCauseCodePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace RoadworksSubCauseCode_Constants { + + + + + + + + + + + } //End of namespace RoadworksSubCauseCode_Constants + RoadworksSubCauseCodePubSubType::RoadworksSubCauseCodePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::RoadworksSubCauseCode_"); + auto type_size = RoadworksSubCauseCode::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = RoadworksSubCauseCode::isKeyDefined(); + size_t keyLength = RoadworksSubCauseCode::getKeyMaxCdrSerializedSize() > 16 ? + RoadworksSubCauseCode::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + RoadworksSubCauseCodePubSubType::~RoadworksSubCauseCodePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool RoadworksSubCauseCodePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + RoadworksSubCauseCode* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool RoadworksSubCauseCodePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + RoadworksSubCauseCode* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function RoadworksSubCauseCodePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* RoadworksSubCauseCodePubSubType::createData() + { + return reinterpret_cast(new RoadworksSubCauseCode()); + } + + void RoadworksSubCauseCodePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool RoadworksSubCauseCodePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + RoadworksSubCauseCode* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + RoadworksSubCauseCode::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || RoadworksSubCauseCode::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCodePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCodePubSubTypes.h new file mode 100644 index 00000000000..6ea5a7a275c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCodePubSubTypes.h @@ -0,0 +1,119 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file RoadworksSubCauseCodePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSSUBCAUSECODE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSSUBCAUSECODE_PUBSUBTYPES_H_ + +#include +#include + +#include "RoadworksSubCauseCode.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated RoadworksSubCauseCode is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace RoadworksSubCauseCode_Constants + { + + + + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type RoadworksSubCauseCode defined by the user in the IDL file. + * @ingroup ROADWORKSSUBCAUSECODE + */ + class RoadworksSubCauseCodePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef RoadworksSubCauseCode type; + + eProsima_user_DllExport RoadworksSubCauseCodePubSubType(); + + eProsima_user_DllExport virtual ~RoadworksSubCauseCodePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) RoadworksSubCauseCode(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSSUBCAUSECODE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainer.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainer.cxx new file mode 100644 index 00000000000..ab332dfa7ba --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainer.cxx @@ -0,0 +1,463 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SafetyCarContainer.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "SafetyCarContainer.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::SafetyCarContainer::SafetyCarContainer() +{ + // m_light_bar_siren_in_use com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@5b58ed3c + + // m_incident_indication com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@24faea88 + + // m_incident_indication_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@3a320ade + m_incident_indication_is_present = false; + // m_traffic_rule com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@64beebb7 + + // m_traffic_rule_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@7813cb11 + m_traffic_rule_is_present = false; + // m_speed_limit com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@bcec031 + + // m_speed_limit_is_present com.eprosima.idl.parser.typecode.PrimitiveTypeCode@21005f6c + m_speed_limit_is_present = false; + +} + +etsi_its_cam_msgs::msg::SafetyCarContainer::~SafetyCarContainer() +{ + + + + + + +} + +etsi_its_cam_msgs::msg::SafetyCarContainer::SafetyCarContainer( + const SafetyCarContainer& x) +{ + m_light_bar_siren_in_use = x.m_light_bar_siren_in_use; + m_incident_indication = x.m_incident_indication; + m_incident_indication_is_present = x.m_incident_indication_is_present; + m_traffic_rule = x.m_traffic_rule; + m_traffic_rule_is_present = x.m_traffic_rule_is_present; + m_speed_limit = x.m_speed_limit; + m_speed_limit_is_present = x.m_speed_limit_is_present; +} + +etsi_its_cam_msgs::msg::SafetyCarContainer::SafetyCarContainer( + SafetyCarContainer&& x) +{ + m_light_bar_siren_in_use = std::move(x.m_light_bar_siren_in_use); + m_incident_indication = std::move(x.m_incident_indication); + m_incident_indication_is_present = x.m_incident_indication_is_present; + m_traffic_rule = std::move(x.m_traffic_rule); + m_traffic_rule_is_present = x.m_traffic_rule_is_present; + m_speed_limit = std::move(x.m_speed_limit); + m_speed_limit_is_present = x.m_speed_limit_is_present; +} + +etsi_its_cam_msgs::msg::SafetyCarContainer& etsi_its_cam_msgs::msg::SafetyCarContainer::operator =( + const SafetyCarContainer& x) +{ + + m_light_bar_siren_in_use = x.m_light_bar_siren_in_use; + m_incident_indication = x.m_incident_indication; + m_incident_indication_is_present = x.m_incident_indication_is_present; + m_traffic_rule = x.m_traffic_rule; + m_traffic_rule_is_present = x.m_traffic_rule_is_present; + m_speed_limit = x.m_speed_limit; + m_speed_limit_is_present = x.m_speed_limit_is_present; + + return *this; +} + +etsi_its_cam_msgs::msg::SafetyCarContainer& etsi_its_cam_msgs::msg::SafetyCarContainer::operator =( + SafetyCarContainer&& x) +{ + + m_light_bar_siren_in_use = std::move(x.m_light_bar_siren_in_use); + m_incident_indication = std::move(x.m_incident_indication); + m_incident_indication_is_present = x.m_incident_indication_is_present; + m_traffic_rule = std::move(x.m_traffic_rule); + m_traffic_rule_is_present = x.m_traffic_rule_is_present; + m_speed_limit = std::move(x.m_speed_limit); + m_speed_limit_is_present = x.m_speed_limit_is_present; + + return *this; +} + +bool etsi_its_cam_msgs::msg::SafetyCarContainer::operator ==( + const SafetyCarContainer& x) const +{ + + return (m_light_bar_siren_in_use == x.m_light_bar_siren_in_use && m_incident_indication == x.m_incident_indication && m_incident_indication_is_present == x.m_incident_indication_is_present && m_traffic_rule == x.m_traffic_rule && m_traffic_rule_is_present == x.m_traffic_rule_is_present && m_speed_limit == x.m_speed_limit && m_speed_limit_is_present == x.m_speed_limit_is_present); +} + +bool etsi_its_cam_msgs::msg::SafetyCarContainer::operator !=( + const SafetyCarContainer& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::SafetyCarContainer::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::LightBarSirenInUse::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::CauseCode::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::TrafficRule::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::SpeedLimit::getMaxCdrSerializedSize(current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::SafetyCarContainer::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SafetyCarContainer& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::LightBarSirenInUse::getCdrSerializedSize(data.light_bar_siren_in_use(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::CauseCode::getCdrSerializedSize(data.incident_indication(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::TrafficRule::getCdrSerializedSize(data.traffic_rule(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::SpeedLimit::getCdrSerializedSize(data.speed_limit(), current_alignment); + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::SafetyCarContainer::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_light_bar_siren_in_use; + scdr << m_incident_indication; + scdr << m_incident_indication_is_present; + scdr << m_traffic_rule; + scdr << m_traffic_rule_is_present; + scdr << m_speed_limit; + scdr << m_speed_limit_is_present; + +} + +void etsi_its_cam_msgs::msg::SafetyCarContainer::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_light_bar_siren_in_use; + dcdr >> m_incident_indication; + dcdr >> m_incident_indication_is_present; + dcdr >> m_traffic_rule; + dcdr >> m_traffic_rule_is_present; + dcdr >> m_speed_limit; + dcdr >> m_speed_limit_is_present; +} + +/*! + * @brief This function copies the value in member light_bar_siren_in_use + * @param _light_bar_siren_in_use New value to be copied in member light_bar_siren_in_use + */ +void etsi_its_cam_msgs::msg::SafetyCarContainer::light_bar_siren_in_use( + const etsi_its_cam_msgs::msg::LightBarSirenInUse& _light_bar_siren_in_use) +{ + m_light_bar_siren_in_use = _light_bar_siren_in_use; +} + +/*! + * @brief This function moves the value in member light_bar_siren_in_use + * @param _light_bar_siren_in_use New value to be moved in member light_bar_siren_in_use + */ +void etsi_its_cam_msgs::msg::SafetyCarContainer::light_bar_siren_in_use( + etsi_its_cam_msgs::msg::LightBarSirenInUse&& _light_bar_siren_in_use) +{ + m_light_bar_siren_in_use = std::move(_light_bar_siren_in_use); +} + +/*! + * @brief This function returns a constant reference to member light_bar_siren_in_use + * @return Constant reference to member light_bar_siren_in_use + */ +const etsi_its_cam_msgs::msg::LightBarSirenInUse& etsi_its_cam_msgs::msg::SafetyCarContainer::light_bar_siren_in_use() const +{ + return m_light_bar_siren_in_use; +} + +/*! + * @brief This function returns a reference to member light_bar_siren_in_use + * @return Reference to member light_bar_siren_in_use + */ +etsi_its_cam_msgs::msg::LightBarSirenInUse& etsi_its_cam_msgs::msg::SafetyCarContainer::light_bar_siren_in_use() +{ + return m_light_bar_siren_in_use; +} +/*! + * @brief This function copies the value in member incident_indication + * @param _incident_indication New value to be copied in member incident_indication + */ +void etsi_its_cam_msgs::msg::SafetyCarContainer::incident_indication( + const etsi_its_cam_msgs::msg::CauseCode& _incident_indication) +{ + m_incident_indication = _incident_indication; +} + +/*! + * @brief This function moves the value in member incident_indication + * @param _incident_indication New value to be moved in member incident_indication + */ +void etsi_its_cam_msgs::msg::SafetyCarContainer::incident_indication( + etsi_its_cam_msgs::msg::CauseCode&& _incident_indication) +{ + m_incident_indication = std::move(_incident_indication); +} + +/*! + * @brief This function returns a constant reference to member incident_indication + * @return Constant reference to member incident_indication + */ +const etsi_its_cam_msgs::msg::CauseCode& etsi_its_cam_msgs::msg::SafetyCarContainer::incident_indication() const +{ + return m_incident_indication; +} + +/*! + * @brief This function returns a reference to member incident_indication + * @return Reference to member incident_indication + */ +etsi_its_cam_msgs::msg::CauseCode& etsi_its_cam_msgs::msg::SafetyCarContainer::incident_indication() +{ + return m_incident_indication; +} +/*! + * @brief This function sets a value in member incident_indication_is_present + * @param _incident_indication_is_present New value for member incident_indication_is_present + */ +void etsi_its_cam_msgs::msg::SafetyCarContainer::incident_indication_is_present( + bool _incident_indication_is_present) +{ + m_incident_indication_is_present = _incident_indication_is_present; +} + +/*! + * @brief This function returns the value of member incident_indication_is_present + * @return Value of member incident_indication_is_present + */ +bool etsi_its_cam_msgs::msg::SafetyCarContainer::incident_indication_is_present() const +{ + return m_incident_indication_is_present; +} + +/*! + * @brief This function returns a reference to member incident_indication_is_present + * @return Reference to member incident_indication_is_present + */ +bool& etsi_its_cam_msgs::msg::SafetyCarContainer::incident_indication_is_present() +{ + return m_incident_indication_is_present; +} + +/*! + * @brief This function copies the value in member traffic_rule + * @param _traffic_rule New value to be copied in member traffic_rule + */ +void etsi_its_cam_msgs::msg::SafetyCarContainer::traffic_rule( + const etsi_its_cam_msgs::msg::TrafficRule& _traffic_rule) +{ + m_traffic_rule = _traffic_rule; +} + +/*! + * @brief This function moves the value in member traffic_rule + * @param _traffic_rule New value to be moved in member traffic_rule + */ +void etsi_its_cam_msgs::msg::SafetyCarContainer::traffic_rule( + etsi_its_cam_msgs::msg::TrafficRule&& _traffic_rule) +{ + m_traffic_rule = std::move(_traffic_rule); +} + +/*! + * @brief This function returns a constant reference to member traffic_rule + * @return Constant reference to member traffic_rule + */ +const etsi_its_cam_msgs::msg::TrafficRule& etsi_its_cam_msgs::msg::SafetyCarContainer::traffic_rule() const +{ + return m_traffic_rule; +} + +/*! + * @brief This function returns a reference to member traffic_rule + * @return Reference to member traffic_rule + */ +etsi_its_cam_msgs::msg::TrafficRule& etsi_its_cam_msgs::msg::SafetyCarContainer::traffic_rule() +{ + return m_traffic_rule; +} +/*! + * @brief This function sets a value in member traffic_rule_is_present + * @param _traffic_rule_is_present New value for member traffic_rule_is_present + */ +void etsi_its_cam_msgs::msg::SafetyCarContainer::traffic_rule_is_present( + bool _traffic_rule_is_present) +{ + m_traffic_rule_is_present = _traffic_rule_is_present; +} + +/*! + * @brief This function returns the value of member traffic_rule_is_present + * @return Value of member traffic_rule_is_present + */ +bool etsi_its_cam_msgs::msg::SafetyCarContainer::traffic_rule_is_present() const +{ + return m_traffic_rule_is_present; +} + +/*! + * @brief This function returns a reference to member traffic_rule_is_present + * @return Reference to member traffic_rule_is_present + */ +bool& etsi_its_cam_msgs::msg::SafetyCarContainer::traffic_rule_is_present() +{ + return m_traffic_rule_is_present; +} + +/*! + * @brief This function copies the value in member speed_limit + * @param _speed_limit New value to be copied in member speed_limit + */ +void etsi_its_cam_msgs::msg::SafetyCarContainer::speed_limit( + const etsi_its_cam_msgs::msg::SpeedLimit& _speed_limit) +{ + m_speed_limit = _speed_limit; +} + +/*! + * @brief This function moves the value in member speed_limit + * @param _speed_limit New value to be moved in member speed_limit + */ +void etsi_its_cam_msgs::msg::SafetyCarContainer::speed_limit( + etsi_its_cam_msgs::msg::SpeedLimit&& _speed_limit) +{ + m_speed_limit = std::move(_speed_limit); +} + +/*! + * @brief This function returns a constant reference to member speed_limit + * @return Constant reference to member speed_limit + */ +const etsi_its_cam_msgs::msg::SpeedLimit& etsi_its_cam_msgs::msg::SafetyCarContainer::speed_limit() const +{ + return m_speed_limit; +} + +/*! + * @brief This function returns a reference to member speed_limit + * @return Reference to member speed_limit + */ +etsi_its_cam_msgs::msg::SpeedLimit& etsi_its_cam_msgs::msg::SafetyCarContainer::speed_limit() +{ + return m_speed_limit; +} +/*! + * @brief This function sets a value in member speed_limit_is_present + * @param _speed_limit_is_present New value for member speed_limit_is_present + */ +void etsi_its_cam_msgs::msg::SafetyCarContainer::speed_limit_is_present( + bool _speed_limit_is_present) +{ + m_speed_limit_is_present = _speed_limit_is_present; +} + +/*! + * @brief This function returns the value of member speed_limit_is_present + * @return Value of member speed_limit_is_present + */ +bool etsi_its_cam_msgs::msg::SafetyCarContainer::speed_limit_is_present() const +{ + return m_speed_limit_is_present; +} + +/*! + * @brief This function returns a reference to member speed_limit_is_present + * @return Reference to member speed_limit_is_present + */ +bool& etsi_its_cam_msgs::msg::SafetyCarContainer::speed_limit_is_present() +{ + return m_speed_limit_is_present; +} + + +size_t etsi_its_cam_msgs::msg::SafetyCarContainer::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::SafetyCarContainer::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::SafetyCarContainer::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainer.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainer.h new file mode 100644 index 00000000000..cc1d65c03db --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainer.h @@ -0,0 +1,358 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SafetyCarContainer.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SAFETYCARCONTAINER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SAFETYCARCONTAINER_H_ + +#include "SpeedLimit.h" +#include "CauseCode.h" +#include "LightBarSirenInUse.h" +#include "TrafficRule.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(SafetyCarContainer_SOURCE) +#define SafetyCarContainer_DllAPI __declspec( dllexport ) +#else +#define SafetyCarContainer_DllAPI __declspec( dllimport ) +#endif // SafetyCarContainer_SOURCE +#else +#define SafetyCarContainer_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define SafetyCarContainer_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure SafetyCarContainer defined by the user in the IDL file. + * @ingroup SAFETYCARCONTAINER + */ + class SafetyCarContainer + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport SafetyCarContainer(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~SafetyCarContainer(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SafetyCarContainer that will be copied. + */ + eProsima_user_DllExport SafetyCarContainer( + const SafetyCarContainer& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SafetyCarContainer that will be copied. + */ + eProsima_user_DllExport SafetyCarContainer( + SafetyCarContainer&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SafetyCarContainer that will be copied. + */ + eProsima_user_DllExport SafetyCarContainer& operator =( + const SafetyCarContainer& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SafetyCarContainer that will be copied. + */ + eProsima_user_DllExport SafetyCarContainer& operator =( + SafetyCarContainer&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SafetyCarContainer object to compare. + */ + eProsima_user_DllExport bool operator ==( + const SafetyCarContainer& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SafetyCarContainer object to compare. + */ + eProsima_user_DllExport bool operator !=( + const SafetyCarContainer& x) const; + + /*! + * @brief This function copies the value in member light_bar_siren_in_use + * @param _light_bar_siren_in_use New value to be copied in member light_bar_siren_in_use + */ + eProsima_user_DllExport void light_bar_siren_in_use( + const etsi_its_cam_msgs::msg::LightBarSirenInUse& _light_bar_siren_in_use); + + /*! + * @brief This function moves the value in member light_bar_siren_in_use + * @param _light_bar_siren_in_use New value to be moved in member light_bar_siren_in_use + */ + eProsima_user_DllExport void light_bar_siren_in_use( + etsi_its_cam_msgs::msg::LightBarSirenInUse&& _light_bar_siren_in_use); + + /*! + * @brief This function returns a constant reference to member light_bar_siren_in_use + * @return Constant reference to member light_bar_siren_in_use + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::LightBarSirenInUse& light_bar_siren_in_use() const; + + /*! + * @brief This function returns a reference to member light_bar_siren_in_use + * @return Reference to member light_bar_siren_in_use + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::LightBarSirenInUse& light_bar_siren_in_use(); + /*! + * @brief This function copies the value in member incident_indication + * @param _incident_indication New value to be copied in member incident_indication + */ + eProsima_user_DllExport void incident_indication( + const etsi_its_cam_msgs::msg::CauseCode& _incident_indication); + + /*! + * @brief This function moves the value in member incident_indication + * @param _incident_indication New value to be moved in member incident_indication + */ + eProsima_user_DllExport void incident_indication( + etsi_its_cam_msgs::msg::CauseCode&& _incident_indication); + + /*! + * @brief This function returns a constant reference to member incident_indication + * @return Constant reference to member incident_indication + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::CauseCode& incident_indication() const; + + /*! + * @brief This function returns a reference to member incident_indication + * @return Reference to member incident_indication + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::CauseCode& incident_indication(); + /*! + * @brief This function sets a value in member incident_indication_is_present + * @param _incident_indication_is_present New value for member incident_indication_is_present + */ + eProsima_user_DllExport void incident_indication_is_present( + bool _incident_indication_is_present); + + /*! + * @brief This function returns the value of member incident_indication_is_present + * @return Value of member incident_indication_is_present + */ + eProsima_user_DllExport bool incident_indication_is_present() const; + + /*! + * @brief This function returns a reference to member incident_indication_is_present + * @return Reference to member incident_indication_is_present + */ + eProsima_user_DllExport bool& incident_indication_is_present(); + + /*! + * @brief This function copies the value in member traffic_rule + * @param _traffic_rule New value to be copied in member traffic_rule + */ + eProsima_user_DllExport void traffic_rule( + const etsi_its_cam_msgs::msg::TrafficRule& _traffic_rule); + + /*! + * @brief This function moves the value in member traffic_rule + * @param _traffic_rule New value to be moved in member traffic_rule + */ + eProsima_user_DllExport void traffic_rule( + etsi_its_cam_msgs::msg::TrafficRule&& _traffic_rule); + + /*! + * @brief This function returns a constant reference to member traffic_rule + * @return Constant reference to member traffic_rule + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::TrafficRule& traffic_rule() const; + + /*! + * @brief This function returns a reference to member traffic_rule + * @return Reference to member traffic_rule + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::TrafficRule& traffic_rule(); + /*! + * @brief This function sets a value in member traffic_rule_is_present + * @param _traffic_rule_is_present New value for member traffic_rule_is_present + */ + eProsima_user_DllExport void traffic_rule_is_present( + bool _traffic_rule_is_present); + + /*! + * @brief This function returns the value of member traffic_rule_is_present + * @return Value of member traffic_rule_is_present + */ + eProsima_user_DllExport bool traffic_rule_is_present() const; + + /*! + * @brief This function returns a reference to member traffic_rule_is_present + * @return Reference to member traffic_rule_is_present + */ + eProsima_user_DllExport bool& traffic_rule_is_present(); + + /*! + * @brief This function copies the value in member speed_limit + * @param _speed_limit New value to be copied in member speed_limit + */ + eProsima_user_DllExport void speed_limit( + const etsi_its_cam_msgs::msg::SpeedLimit& _speed_limit); + + /*! + * @brief This function moves the value in member speed_limit + * @param _speed_limit New value to be moved in member speed_limit + */ + eProsima_user_DllExport void speed_limit( + etsi_its_cam_msgs::msg::SpeedLimit&& _speed_limit); + + /*! + * @brief This function returns a constant reference to member speed_limit + * @return Constant reference to member speed_limit + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::SpeedLimit& speed_limit() const; + + /*! + * @brief This function returns a reference to member speed_limit + * @return Reference to member speed_limit + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::SpeedLimit& speed_limit(); + /*! + * @brief This function sets a value in member speed_limit_is_present + * @param _speed_limit_is_present New value for member speed_limit_is_present + */ + eProsima_user_DllExport void speed_limit_is_present( + bool _speed_limit_is_present); + + /*! + * @brief This function returns the value of member speed_limit_is_present + * @return Value of member speed_limit_is_present + */ + eProsima_user_DllExport bool speed_limit_is_present() const; + + /*! + * @brief This function returns a reference to member speed_limit_is_present + * @return Reference to member speed_limit_is_present + */ + eProsima_user_DllExport bool& speed_limit_is_present(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SafetyCarContainer& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::LightBarSirenInUse m_light_bar_siren_in_use; + etsi_its_cam_msgs::msg::CauseCode m_incident_indication; + bool m_incident_indication_is_present; + etsi_its_cam_msgs::msg::TrafficRule m_traffic_rule; + bool m_traffic_rule_is_present; + etsi_its_cam_msgs::msg::SpeedLimit m_speed_limit; + bool m_speed_limit_is_present; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SAFETYCARCONTAINER_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainerPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainerPubSubTypes.cxx new file mode 100644 index 00000000000..1c39058a1b1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainerPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SafetyCarContainerPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "SafetyCarContainerPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + SafetyCarContainerPubSubType::SafetyCarContainerPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::SafetyCarContainer_"); + auto type_size = SafetyCarContainer::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = SafetyCarContainer::isKeyDefined(); + size_t keyLength = SafetyCarContainer::getKeyMaxCdrSerializedSize() > 16 ? + SafetyCarContainer::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + SafetyCarContainerPubSubType::~SafetyCarContainerPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool SafetyCarContainerPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + SafetyCarContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool SafetyCarContainerPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + SafetyCarContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function SafetyCarContainerPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* SafetyCarContainerPubSubType::createData() + { + return reinterpret_cast(new SafetyCarContainer()); + } + + void SafetyCarContainerPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool SafetyCarContainerPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + SafetyCarContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + SafetyCarContainer::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || SafetyCarContainer::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainerPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainerPubSubTypes.h new file mode 100644 index 00000000000..f0770ab0dcd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainerPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SafetyCarContainerPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SAFETYCARCONTAINER_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SAFETYCARCONTAINER_PUBSUBTYPES_H_ + +#include +#include + +#include "SafetyCarContainer.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated SafetyCarContainer is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type SafetyCarContainer defined by the user in the IDL file. + * @ingroup SAFETYCARCONTAINER + */ + class SafetyCarContainerPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef SafetyCarContainer type; + + eProsima_user_DllExport SafetyCarContainerPubSubType(); + + eProsima_user_DllExport virtual ~SafetyCarContainerPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SAFETYCARCONTAINER_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLength.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLength.cxx new file mode 100644 index 00000000000..4db3bb66bd7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLength.cxx @@ -0,0 +1,189 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SemiAxisLength.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "SemiAxisLength.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + +etsi_its_cam_msgs::msg::SemiAxisLength::SemiAxisLength() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@109d724c + m_value = 0; + +} + +etsi_its_cam_msgs::msg::SemiAxisLength::~SemiAxisLength() +{ +} + +etsi_its_cam_msgs::msg::SemiAxisLength::SemiAxisLength( + const SemiAxisLength& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::SemiAxisLength::SemiAxisLength( + SemiAxisLength&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::SemiAxisLength& etsi_its_cam_msgs::msg::SemiAxisLength::operator =( + const SemiAxisLength& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::SemiAxisLength& etsi_its_cam_msgs::msg::SemiAxisLength::operator =( + SemiAxisLength&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::SemiAxisLength::operator ==( + const SemiAxisLength& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::SemiAxisLength::operator !=( + const SemiAxisLength& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::SemiAxisLength::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::SemiAxisLength::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SemiAxisLength& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::SemiAxisLength::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::SemiAxisLength::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::SemiAxisLength::value( + uint16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint16_t etsi_its_cam_msgs::msg::SemiAxisLength::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint16_t& etsi_its_cam_msgs::msg::SemiAxisLength::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::SemiAxisLength::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::SemiAxisLength::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::SemiAxisLength::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLength.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLength.h new file mode 100644 index 00000000000..42d59a56d62 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLength.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SemiAxisLength.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SEMIAXISLENGTH_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SEMIAXISLENGTH_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(SemiAxisLength_SOURCE) +#define SemiAxisLength_DllAPI __declspec( dllexport ) +#else +#define SemiAxisLength_DllAPI __declspec( dllimport ) +#endif // SemiAxisLength_SOURCE +#else +#define SemiAxisLength_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define SemiAxisLength_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace SemiAxisLength_Constants { + const uint16_t MIN = 0; + const uint16_t MAX = 4095; + const uint16_t ONE_CENTIMETER = 1; + const uint16_t OUT_OF_RANGE = 4094; + const uint16_t UNAVAILABLE = 4095; + } // namespace SemiAxisLength_Constants + /*! + * @brief This class represents the structure SemiAxisLength defined by the user in the IDL file. + * @ingroup SEMIAXISLENGTH + */ + class SemiAxisLength + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport SemiAxisLength(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~SemiAxisLength(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SemiAxisLength that will be copied. + */ + eProsima_user_DllExport SemiAxisLength( + const SemiAxisLength& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SemiAxisLength that will be copied. + */ + eProsima_user_DllExport SemiAxisLength( + SemiAxisLength&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SemiAxisLength that will be copied. + */ + eProsima_user_DllExport SemiAxisLength& operator =( + const SemiAxisLength& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SemiAxisLength that will be copied. + */ + eProsima_user_DllExport SemiAxisLength& operator =( + SemiAxisLength&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SemiAxisLength object to compare. + */ + eProsima_user_DllExport bool operator ==( + const SemiAxisLength& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SemiAxisLength object to compare. + */ + eProsima_user_DllExport bool operator !=( + const SemiAxisLength& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint16_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint16_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint16_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SemiAxisLength& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint16_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SEMIAXISLENGTH_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLengthPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLengthPubSubTypes.cxx new file mode 100644 index 00000000000..53e4abd9bab --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLengthPubSubTypes.cxx @@ -0,0 +1,184 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SemiAxisLengthPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "SemiAxisLengthPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace SemiAxisLength_Constants { + + + + + + + } //End of namespace SemiAxisLength_Constants + SemiAxisLengthPubSubType::SemiAxisLengthPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::SemiAxisLength_"); + auto type_size = SemiAxisLength::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = SemiAxisLength::isKeyDefined(); + size_t keyLength = SemiAxisLength::getKeyMaxCdrSerializedSize() > 16 ? + SemiAxisLength::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + SemiAxisLengthPubSubType::~SemiAxisLengthPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool SemiAxisLengthPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + SemiAxisLength* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool SemiAxisLengthPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + SemiAxisLength* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function SemiAxisLengthPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* SemiAxisLengthPubSubType::createData() + { + return reinterpret_cast(new SemiAxisLength()); + } + + void SemiAxisLengthPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool SemiAxisLengthPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + SemiAxisLength* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + SemiAxisLength::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || SemiAxisLength::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLengthPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLengthPubSubTypes.h new file mode 100644 index 00000000000..ecf8b8f362d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLengthPubSubTypes.h @@ -0,0 +1,115 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SemiAxisLengthPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SEMIAXISLENGTH_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SEMIAXISLENGTH_PUBSUBTYPES_H_ + +#include +#include + +#include "SemiAxisLength.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated SemiAxisLength is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace SemiAxisLength_Constants + { + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type SemiAxisLength defined by the user in the IDL file. + * @ingroup SEMIAXISLENGTH + */ + class SemiAxisLengthPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef SemiAxisLength type; + + eProsima_user_DllExport SemiAxisLengthPubSubType(); + + eProsima_user_DllExport virtual ~SemiAxisLengthPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) SemiAxisLength(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SEMIAXISLENGTH_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainer.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainer.cxx new file mode 100644 index 00000000000..7c8f9ec8d9e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainer.cxx @@ -0,0 +1,238 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpecialTransportContainer.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "SpecialTransportContainer.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::SpecialTransportContainer::SpecialTransportContainer() +{ + // m_special_transport_type com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@9bd0fa6 + + // m_light_bar_siren_in_use com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@59d2103b + + +} + +etsi_its_cam_msgs::msg::SpecialTransportContainer::~SpecialTransportContainer() +{ + +} + +etsi_its_cam_msgs::msg::SpecialTransportContainer::SpecialTransportContainer( + const SpecialTransportContainer& x) +{ + m_special_transport_type = x.m_special_transport_type; + m_light_bar_siren_in_use = x.m_light_bar_siren_in_use; +} + +etsi_its_cam_msgs::msg::SpecialTransportContainer::SpecialTransportContainer( + SpecialTransportContainer&& x) +{ + m_special_transport_type = std::move(x.m_special_transport_type); + m_light_bar_siren_in_use = std::move(x.m_light_bar_siren_in_use); +} + +etsi_its_cam_msgs::msg::SpecialTransportContainer& etsi_its_cam_msgs::msg::SpecialTransportContainer::operator =( + const SpecialTransportContainer& x) +{ + + m_special_transport_type = x.m_special_transport_type; + m_light_bar_siren_in_use = x.m_light_bar_siren_in_use; + + return *this; +} + +etsi_its_cam_msgs::msg::SpecialTransportContainer& etsi_its_cam_msgs::msg::SpecialTransportContainer::operator =( + SpecialTransportContainer&& x) +{ + + m_special_transport_type = std::move(x.m_special_transport_type); + m_light_bar_siren_in_use = std::move(x.m_light_bar_siren_in_use); + + return *this; +} + +bool etsi_its_cam_msgs::msg::SpecialTransportContainer::operator ==( + const SpecialTransportContainer& x) const +{ + + return (m_special_transport_type == x.m_special_transport_type && m_light_bar_siren_in_use == x.m_light_bar_siren_in_use); +} + +bool etsi_its_cam_msgs::msg::SpecialTransportContainer::operator !=( + const SpecialTransportContainer& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::SpecialTransportContainer::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::SpecialTransportType::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::LightBarSirenInUse::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::SpecialTransportContainer::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SpecialTransportContainer& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::SpecialTransportType::getCdrSerializedSize(data.special_transport_type(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::LightBarSirenInUse::getCdrSerializedSize(data.light_bar_siren_in_use(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::SpecialTransportContainer::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_special_transport_type; + scdr << m_light_bar_siren_in_use; + +} + +void etsi_its_cam_msgs::msg::SpecialTransportContainer::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_special_transport_type; + dcdr >> m_light_bar_siren_in_use; +} + +/*! + * @brief This function copies the value in member special_transport_type + * @param _special_transport_type New value to be copied in member special_transport_type + */ +void etsi_its_cam_msgs::msg::SpecialTransportContainer::special_transport_type( + const etsi_its_cam_msgs::msg::SpecialTransportType& _special_transport_type) +{ + m_special_transport_type = _special_transport_type; +} + +/*! + * @brief This function moves the value in member special_transport_type + * @param _special_transport_type New value to be moved in member special_transport_type + */ +void etsi_its_cam_msgs::msg::SpecialTransportContainer::special_transport_type( + etsi_its_cam_msgs::msg::SpecialTransportType&& _special_transport_type) +{ + m_special_transport_type = std::move(_special_transport_type); +} + +/*! + * @brief This function returns a constant reference to member special_transport_type + * @return Constant reference to member special_transport_type + */ +const etsi_its_cam_msgs::msg::SpecialTransportType& etsi_its_cam_msgs::msg::SpecialTransportContainer::special_transport_type() const +{ + return m_special_transport_type; +} + +/*! + * @brief This function returns a reference to member special_transport_type + * @return Reference to member special_transport_type + */ +etsi_its_cam_msgs::msg::SpecialTransportType& etsi_its_cam_msgs::msg::SpecialTransportContainer::special_transport_type() +{ + return m_special_transport_type; +} +/*! + * @brief This function copies the value in member light_bar_siren_in_use + * @param _light_bar_siren_in_use New value to be copied in member light_bar_siren_in_use + */ +void etsi_its_cam_msgs::msg::SpecialTransportContainer::light_bar_siren_in_use( + const etsi_its_cam_msgs::msg::LightBarSirenInUse& _light_bar_siren_in_use) +{ + m_light_bar_siren_in_use = _light_bar_siren_in_use; +} + +/*! + * @brief This function moves the value in member light_bar_siren_in_use + * @param _light_bar_siren_in_use New value to be moved in member light_bar_siren_in_use + */ +void etsi_its_cam_msgs::msg::SpecialTransportContainer::light_bar_siren_in_use( + etsi_its_cam_msgs::msg::LightBarSirenInUse&& _light_bar_siren_in_use) +{ + m_light_bar_siren_in_use = std::move(_light_bar_siren_in_use); +} + +/*! + * @brief This function returns a constant reference to member light_bar_siren_in_use + * @return Constant reference to member light_bar_siren_in_use + */ +const etsi_its_cam_msgs::msg::LightBarSirenInUse& etsi_its_cam_msgs::msg::SpecialTransportContainer::light_bar_siren_in_use() const +{ + return m_light_bar_siren_in_use; +} + +/*! + * @brief This function returns a reference to member light_bar_siren_in_use + * @return Reference to member light_bar_siren_in_use + */ +etsi_its_cam_msgs::msg::LightBarSirenInUse& etsi_its_cam_msgs::msg::SpecialTransportContainer::light_bar_siren_in_use() +{ + return m_light_bar_siren_in_use; +} + +size_t etsi_its_cam_msgs::msg::SpecialTransportContainer::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::SpecialTransportContainer::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::SpecialTransportContainer::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainer.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainer.h new file mode 100644 index 00000000000..33bd8613f87 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainer.h @@ -0,0 +1,244 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpecialTransportContainer.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTCONTAINER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTCONTAINER_H_ + +#include "SpecialTransportType.h" +#include "LightBarSirenInUse.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(SpecialTransportContainer_SOURCE) +#define SpecialTransportContainer_DllAPI __declspec( dllexport ) +#else +#define SpecialTransportContainer_DllAPI __declspec( dllimport ) +#endif // SpecialTransportContainer_SOURCE +#else +#define SpecialTransportContainer_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define SpecialTransportContainer_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure SpecialTransportContainer defined by the user in the IDL file. + * @ingroup SPECIALTRANSPORTCONTAINER + */ + class SpecialTransportContainer + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport SpecialTransportContainer(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~SpecialTransportContainer(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpecialTransportContainer that will be copied. + */ + eProsima_user_DllExport SpecialTransportContainer( + const SpecialTransportContainer& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpecialTransportContainer that will be copied. + */ + eProsima_user_DllExport SpecialTransportContainer( + SpecialTransportContainer&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpecialTransportContainer that will be copied. + */ + eProsima_user_DllExport SpecialTransportContainer& operator =( + const SpecialTransportContainer& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpecialTransportContainer that will be copied. + */ + eProsima_user_DllExport SpecialTransportContainer& operator =( + SpecialTransportContainer&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SpecialTransportContainer object to compare. + */ + eProsima_user_DllExport bool operator ==( + const SpecialTransportContainer& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SpecialTransportContainer object to compare. + */ + eProsima_user_DllExport bool operator !=( + const SpecialTransportContainer& x) const; + + /*! + * @brief This function copies the value in member special_transport_type + * @param _special_transport_type New value to be copied in member special_transport_type + */ + eProsima_user_DllExport void special_transport_type( + const etsi_its_cam_msgs::msg::SpecialTransportType& _special_transport_type); + + /*! + * @brief This function moves the value in member special_transport_type + * @param _special_transport_type New value to be moved in member special_transport_type + */ + eProsima_user_DllExport void special_transport_type( + etsi_its_cam_msgs::msg::SpecialTransportType&& _special_transport_type); + + /*! + * @brief This function returns a constant reference to member special_transport_type + * @return Constant reference to member special_transport_type + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::SpecialTransportType& special_transport_type() const; + + /*! + * @brief This function returns a reference to member special_transport_type + * @return Reference to member special_transport_type + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::SpecialTransportType& special_transport_type(); + /*! + * @brief This function copies the value in member light_bar_siren_in_use + * @param _light_bar_siren_in_use New value to be copied in member light_bar_siren_in_use + */ + eProsima_user_DllExport void light_bar_siren_in_use( + const etsi_its_cam_msgs::msg::LightBarSirenInUse& _light_bar_siren_in_use); + + /*! + * @brief This function moves the value in member light_bar_siren_in_use + * @param _light_bar_siren_in_use New value to be moved in member light_bar_siren_in_use + */ + eProsima_user_DllExport void light_bar_siren_in_use( + etsi_its_cam_msgs::msg::LightBarSirenInUse&& _light_bar_siren_in_use); + + /*! + * @brief This function returns a constant reference to member light_bar_siren_in_use + * @return Constant reference to member light_bar_siren_in_use + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::LightBarSirenInUse& light_bar_siren_in_use() const; + + /*! + * @brief This function returns a reference to member light_bar_siren_in_use + * @return Reference to member light_bar_siren_in_use + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::LightBarSirenInUse& light_bar_siren_in_use(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SpecialTransportContainer& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::SpecialTransportType m_special_transport_type; + etsi_its_cam_msgs::msg::LightBarSirenInUse m_light_bar_siren_in_use; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTCONTAINER_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainerPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainerPubSubTypes.cxx new file mode 100644 index 00000000000..2133fa070e7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainerPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpecialTransportContainerPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "SpecialTransportContainerPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + SpecialTransportContainerPubSubType::SpecialTransportContainerPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::SpecialTransportContainer_"); + auto type_size = SpecialTransportContainer::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = SpecialTransportContainer::isKeyDefined(); + size_t keyLength = SpecialTransportContainer::getKeyMaxCdrSerializedSize() > 16 ? + SpecialTransportContainer::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + SpecialTransportContainerPubSubType::~SpecialTransportContainerPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool SpecialTransportContainerPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + SpecialTransportContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool SpecialTransportContainerPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + SpecialTransportContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function SpecialTransportContainerPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* SpecialTransportContainerPubSubType::createData() + { + return reinterpret_cast(new SpecialTransportContainer()); + } + + void SpecialTransportContainerPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool SpecialTransportContainerPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + SpecialTransportContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + SpecialTransportContainer::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || SpecialTransportContainer::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainerPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainerPubSubTypes.h new file mode 100644 index 00000000000..b1b215b7ecb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainerPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpecialTransportContainerPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTCONTAINER_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTCONTAINER_PUBSUBTYPES_H_ + +#include +#include + +#include "SpecialTransportContainer.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated SpecialTransportContainer is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type SpecialTransportContainer defined by the user in the IDL file. + * @ingroup SPECIALTRANSPORTCONTAINER + */ + class SpecialTransportContainerPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef SpecialTransportContainer type; + + eProsima_user_DllExport SpecialTransportContainerPubSubType(); + + eProsima_user_DllExport virtual ~SpecialTransportContainerPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTCONTAINER_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportType.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportType.cxx new file mode 100644 index 00000000000..a78fde6112c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportType.cxx @@ -0,0 +1,252 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpecialTransportType.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "SpecialTransportType.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + +etsi_its_cam_msgs::msg::SpecialTransportType::SpecialTransportType() +{ + // m_value com.eprosima.idl.parser.typecode.SequenceTypeCode@4ae33a11 + + // m_bits_unused com.eprosima.idl.parser.typecode.PrimitiveTypeCode@7a48e6e2 + m_bits_unused = 0; + +} + +etsi_its_cam_msgs::msg::SpecialTransportType::~SpecialTransportType() +{ + +} + +etsi_its_cam_msgs::msg::SpecialTransportType::SpecialTransportType( + const SpecialTransportType& x) +{ + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; +} + +etsi_its_cam_msgs::msg::SpecialTransportType::SpecialTransportType( + SpecialTransportType&& x) +{ + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; +} + +etsi_its_cam_msgs::msg::SpecialTransportType& etsi_its_cam_msgs::msg::SpecialTransportType::operator =( + const SpecialTransportType& x) +{ + + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; + + return *this; +} + +etsi_its_cam_msgs::msg::SpecialTransportType& etsi_its_cam_msgs::msg::SpecialTransportType::operator =( + SpecialTransportType&& x) +{ + + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; + + return *this; +} + +bool etsi_its_cam_msgs::msg::SpecialTransportType::operator ==( + const SpecialTransportType& x) const +{ + + return (m_value == x.m_value && m_bits_unused == x.m_bits_unused); +} + +bool etsi_its_cam_msgs::msg::SpecialTransportType::operator !=( + const SpecialTransportType& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::SpecialTransportType::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + current_alignment += (100 * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::SpecialTransportType::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SpecialTransportType& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + if (data.value().size() > 0) + { + current_alignment += (data.value().size() * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + } + + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::SpecialTransportType::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + scdr << m_bits_unused; + +} + +void etsi_its_cam_msgs::msg::SpecialTransportType::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; + dcdr >> m_bits_unused; +} + +/*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ +void etsi_its_cam_msgs::msg::SpecialTransportType::value( + const std::vector& _value) +{ + m_value = _value; +} + +/*! + * @brief This function moves the value in member value + * @param _value New value to be moved in member value + */ +void etsi_its_cam_msgs::msg::SpecialTransportType::value( + std::vector&& _value) +{ + m_value = std::move(_value); +} + +/*! + * @brief This function returns a constant reference to member value + * @return Constant reference to member value + */ +const std::vector& etsi_its_cam_msgs::msg::SpecialTransportType::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +std::vector& etsi_its_cam_msgs::msg::SpecialTransportType::value() +{ + return m_value; +} +/*! + * @brief This function sets a value in member bits_unused + * @param _bits_unused New value for member bits_unused + */ +void etsi_its_cam_msgs::msg::SpecialTransportType::bits_unused( + uint8_t _bits_unused) +{ + m_bits_unused = _bits_unused; +} + +/*! + * @brief This function returns the value of member bits_unused + * @return Value of member bits_unused + */ +uint8_t etsi_its_cam_msgs::msg::SpecialTransportType::bits_unused() const +{ + return m_bits_unused; +} + +/*! + * @brief This function returns a reference to member bits_unused + * @return Reference to member bits_unused + */ +uint8_t& etsi_its_cam_msgs::msg::SpecialTransportType::bits_unused() +{ + return m_bits_unused; +} + + +size_t etsi_its_cam_msgs::msg::SpecialTransportType::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::SpecialTransportType::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::SpecialTransportType::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportType.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportType.h new file mode 100644 index 00000000000..7782f292b84 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportType.h @@ -0,0 +1,243 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpecialTransportType.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTTYPE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTTYPE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(SpecialTransportType_SOURCE) +#define SpecialTransportType_DllAPI __declspec( dllexport ) +#else +#define SpecialTransportType_DllAPI __declspec( dllimport ) +#endif // SpecialTransportType_SOURCE +#else +#define SpecialTransportType_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define SpecialTransportType_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace SpecialTransportType_Constants { + const uint8_t SIZE_BITS = 4; + const uint8_t BIT_INDEX_HEAVY_LOAD = 0; + const uint8_t BIT_INDEX_EXCESS_WIDTH = 1; + const uint8_t BIT_INDEX_EXCESS_LENGTH = 2; + const uint8_t BIT_INDEX_EXCESS_HEIGHT = 3; + } // namespace SpecialTransportType_Constants + /*! + * @brief This class represents the structure SpecialTransportType defined by the user in the IDL file. + * @ingroup SPECIALTRANSPORTTYPE + */ + class SpecialTransportType + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport SpecialTransportType(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~SpecialTransportType(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpecialTransportType that will be copied. + */ + eProsima_user_DllExport SpecialTransportType( + const SpecialTransportType& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpecialTransportType that will be copied. + */ + eProsima_user_DllExport SpecialTransportType( + SpecialTransportType&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpecialTransportType that will be copied. + */ + eProsima_user_DllExport SpecialTransportType& operator =( + const SpecialTransportType& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpecialTransportType that will be copied. + */ + eProsima_user_DllExport SpecialTransportType& operator =( + SpecialTransportType&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SpecialTransportType object to compare. + */ + eProsima_user_DllExport bool operator ==( + const SpecialTransportType& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SpecialTransportType object to compare. + */ + eProsima_user_DllExport bool operator !=( + const SpecialTransportType& x) const; + + /*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ + eProsima_user_DllExport void value( + const std::vector& _value); + + /*! + * @brief This function moves the value in member value + * @param _value New value to be moved in member value + */ + eProsima_user_DllExport void value( + std::vector&& _value); + + /*! + * @brief This function returns a constant reference to member value + * @return Constant reference to member value + */ + eProsima_user_DllExport const std::vector& value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport std::vector& value(); + /*! + * @brief This function sets a value in member bits_unused + * @param _bits_unused New value for member bits_unused + */ + eProsima_user_DllExport void bits_unused( + uint8_t _bits_unused); + + /*! + * @brief This function returns the value of member bits_unused + * @return Value of member bits_unused + */ + eProsima_user_DllExport uint8_t bits_unused() const; + + /*! + * @brief This function returns a reference to member bits_unused + * @return Reference to member bits_unused + */ + eProsima_user_DllExport uint8_t& bits_unused(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SpecialTransportType& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + std::vector m_value; + uint8_t m_bits_unused; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTTYPE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportTypePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportTypePubSubTypes.cxx new file mode 100644 index 00000000000..4cf1d4b6bbb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportTypePubSubTypes.cxx @@ -0,0 +1,184 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpecialTransportTypePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "SpecialTransportTypePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace SpecialTransportType_Constants { + + + + + + + } //End of namespace SpecialTransportType_Constants + SpecialTransportTypePubSubType::SpecialTransportTypePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::SpecialTransportType_"); + auto type_size = SpecialTransportType::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = SpecialTransportType::isKeyDefined(); + size_t keyLength = SpecialTransportType::getKeyMaxCdrSerializedSize() > 16 ? + SpecialTransportType::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + SpecialTransportTypePubSubType::~SpecialTransportTypePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool SpecialTransportTypePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + SpecialTransportType* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool SpecialTransportTypePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + SpecialTransportType* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function SpecialTransportTypePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* SpecialTransportTypePubSubType::createData() + { + return reinterpret_cast(new SpecialTransportType()); + } + + void SpecialTransportTypePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool SpecialTransportTypePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + SpecialTransportType* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + SpecialTransportType::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || SpecialTransportType::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportTypePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportTypePubSubTypes.h new file mode 100644 index 00000000000..4ba09070054 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportTypePubSubTypes.h @@ -0,0 +1,115 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpecialTransportTypePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTTYPE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTTYPE_PUBSUBTYPES_H_ + +#include +#include + +#include "SpecialTransportType.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated SpecialTransportType is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace SpecialTransportType_Constants + { + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type SpecialTransportType defined by the user in the IDL file. + * @ingroup SPECIALTRANSPORTTYPE + */ + class SpecialTransportTypePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef SpecialTransportType type; + + eProsima_user_DllExport SpecialTransportTypePubSubType(); + + eProsima_user_DllExport virtual ~SpecialTransportTypePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTTYPE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainer.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainer.cxx new file mode 100644 index 00000000000..cfe1e0a9ecc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainer.cxx @@ -0,0 +1,529 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpecialVehicleContainer.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "SpecialVehicleContainer.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + + +etsi_its_cam_msgs::msg::SpecialVehicleContainer::SpecialVehicleContainer() +{ + // m_choice com.eprosima.idl.parser.typecode.PrimitiveTypeCode@4275c20c + m_choice = 0; + // m_public_transport_container com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@7c56e013 + + // m_special_transport_container com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@3fc9dfc5 + + // m_dangerous_goods_container com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@40258c2f + + // m_road_works_container_basic com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@2cac4385 + + // m_rescue_container com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@6731787b + + // m_emergency_container com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@16f7b4af + + // m_safety_car_container com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@7adf16aa + + +} + +etsi_its_cam_msgs::msg::SpecialVehicleContainer::~SpecialVehicleContainer() +{ + + + + + + + +} + +etsi_its_cam_msgs::msg::SpecialVehicleContainer::SpecialVehicleContainer( + const SpecialVehicleContainer& x) +{ + m_choice = x.m_choice; + m_public_transport_container = x.m_public_transport_container; + m_special_transport_container = x.m_special_transport_container; + m_dangerous_goods_container = x.m_dangerous_goods_container; + m_road_works_container_basic = x.m_road_works_container_basic; + m_rescue_container = x.m_rescue_container; + m_emergency_container = x.m_emergency_container; + m_safety_car_container = x.m_safety_car_container; +} + +etsi_its_cam_msgs::msg::SpecialVehicleContainer::SpecialVehicleContainer( + SpecialVehicleContainer&& x) +{ + m_choice = x.m_choice; + m_public_transport_container = std::move(x.m_public_transport_container); + m_special_transport_container = std::move(x.m_special_transport_container); + m_dangerous_goods_container = std::move(x.m_dangerous_goods_container); + m_road_works_container_basic = std::move(x.m_road_works_container_basic); + m_rescue_container = std::move(x.m_rescue_container); + m_emergency_container = std::move(x.m_emergency_container); + m_safety_car_container = std::move(x.m_safety_car_container); +} + +etsi_its_cam_msgs::msg::SpecialVehicleContainer& etsi_its_cam_msgs::msg::SpecialVehicleContainer::operator =( + const SpecialVehicleContainer& x) +{ + + m_choice = x.m_choice; + m_public_transport_container = x.m_public_transport_container; + m_special_transport_container = x.m_special_transport_container; + m_dangerous_goods_container = x.m_dangerous_goods_container; + m_road_works_container_basic = x.m_road_works_container_basic; + m_rescue_container = x.m_rescue_container; + m_emergency_container = x.m_emergency_container; + m_safety_car_container = x.m_safety_car_container; + + return *this; +} + +etsi_its_cam_msgs::msg::SpecialVehicleContainer& etsi_its_cam_msgs::msg::SpecialVehicleContainer::operator =( + SpecialVehicleContainer&& x) +{ + + m_choice = x.m_choice; + m_public_transport_container = std::move(x.m_public_transport_container); + m_special_transport_container = std::move(x.m_special_transport_container); + m_dangerous_goods_container = std::move(x.m_dangerous_goods_container); + m_road_works_container_basic = std::move(x.m_road_works_container_basic); + m_rescue_container = std::move(x.m_rescue_container); + m_emergency_container = std::move(x.m_emergency_container); + m_safety_car_container = std::move(x.m_safety_car_container); + + return *this; +} + +bool etsi_its_cam_msgs::msg::SpecialVehicleContainer::operator ==( + const SpecialVehicleContainer& x) const +{ + + return (m_choice == x.m_choice && m_public_transport_container == x.m_public_transport_container && m_special_transport_container == x.m_special_transport_container && m_dangerous_goods_container == x.m_dangerous_goods_container && m_road_works_container_basic == x.m_road_works_container_basic && m_rescue_container == x.m_rescue_container && m_emergency_container == x.m_emergency_container && m_safety_car_container == x.m_safety_car_container); +} + +bool etsi_its_cam_msgs::msg::SpecialVehicleContainer::operator !=( + const SpecialVehicleContainer& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::SpecialVehicleContainer::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::PublicTransportContainer::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::SpecialTransportContainer::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::DangerousGoodsContainer::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::RoadWorksContainerBasic::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::RescueContainer::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::EmergencyContainer::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::SafetyCarContainer::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::SpecialVehicleContainer::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SpecialVehicleContainer& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += etsi_its_cam_msgs::msg::PublicTransportContainer::getCdrSerializedSize(data.public_transport_container(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::SpecialTransportContainer::getCdrSerializedSize(data.special_transport_container(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::DangerousGoodsContainer::getCdrSerializedSize(data.dangerous_goods_container(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::RoadWorksContainerBasic::getCdrSerializedSize(data.road_works_container_basic(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::RescueContainer::getCdrSerializedSize(data.rescue_container(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::EmergencyContainer::getCdrSerializedSize(data.emergency_container(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::SafetyCarContainer::getCdrSerializedSize(data.safety_car_container(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::SpecialVehicleContainer::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_choice; + scdr << m_public_transport_container; + scdr << m_special_transport_container; + scdr << m_dangerous_goods_container; + scdr << m_road_works_container_basic; + scdr << m_rescue_container; + scdr << m_emergency_container; + scdr << m_safety_car_container; + +} + +void etsi_its_cam_msgs::msg::SpecialVehicleContainer::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_choice; + dcdr >> m_public_transport_container; + dcdr >> m_special_transport_container; + dcdr >> m_dangerous_goods_container; + dcdr >> m_road_works_container_basic; + dcdr >> m_rescue_container; + dcdr >> m_emergency_container; + dcdr >> m_safety_car_container; +} + +/*! + * @brief This function sets a value in member choice + * @param _choice New value for member choice + */ +void etsi_its_cam_msgs::msg::SpecialVehicleContainer::choice( + uint8_t _choice) +{ + m_choice = _choice; +} + +/*! + * @brief This function returns the value of member choice + * @return Value of member choice + */ +uint8_t etsi_its_cam_msgs::msg::SpecialVehicleContainer::choice() const +{ + return m_choice; +} + +/*! + * @brief This function returns a reference to member choice + * @return Reference to member choice + */ +uint8_t& etsi_its_cam_msgs::msg::SpecialVehicleContainer::choice() +{ + return m_choice; +} + +/*! + * @brief This function copies the value in member public_transport_container + * @param _public_transport_container New value to be copied in member public_transport_container + */ +void etsi_its_cam_msgs::msg::SpecialVehicleContainer::public_transport_container( + const etsi_its_cam_msgs::msg::PublicTransportContainer& _public_transport_container) +{ + m_public_transport_container = _public_transport_container; +} + +/*! + * @brief This function moves the value in member public_transport_container + * @param _public_transport_container New value to be moved in member public_transport_container + */ +void etsi_its_cam_msgs::msg::SpecialVehicleContainer::public_transport_container( + etsi_its_cam_msgs::msg::PublicTransportContainer&& _public_transport_container) +{ + m_public_transport_container = std::move(_public_transport_container); +} + +/*! + * @brief This function returns a constant reference to member public_transport_container + * @return Constant reference to member public_transport_container + */ +const etsi_its_cam_msgs::msg::PublicTransportContainer& etsi_its_cam_msgs::msg::SpecialVehicleContainer::public_transport_container() const +{ + return m_public_transport_container; +} + +/*! + * @brief This function returns a reference to member public_transport_container + * @return Reference to member public_transport_container + */ +etsi_its_cam_msgs::msg::PublicTransportContainer& etsi_its_cam_msgs::msg::SpecialVehicleContainer::public_transport_container() +{ + return m_public_transport_container; +} +/*! + * @brief This function copies the value in member special_transport_container + * @param _special_transport_container New value to be copied in member special_transport_container + */ +void etsi_its_cam_msgs::msg::SpecialVehicleContainer::special_transport_container( + const etsi_its_cam_msgs::msg::SpecialTransportContainer& _special_transport_container) +{ + m_special_transport_container = _special_transport_container; +} + +/*! + * @brief This function moves the value in member special_transport_container + * @param _special_transport_container New value to be moved in member special_transport_container + */ +void etsi_its_cam_msgs::msg::SpecialVehicleContainer::special_transport_container( + etsi_its_cam_msgs::msg::SpecialTransportContainer&& _special_transport_container) +{ + m_special_transport_container = std::move(_special_transport_container); +} + +/*! + * @brief This function returns a constant reference to member special_transport_container + * @return Constant reference to member special_transport_container + */ +const etsi_its_cam_msgs::msg::SpecialTransportContainer& etsi_its_cam_msgs::msg::SpecialVehicleContainer::special_transport_container() const +{ + return m_special_transport_container; +} + +/*! + * @brief This function returns a reference to member special_transport_container + * @return Reference to member special_transport_container + */ +etsi_its_cam_msgs::msg::SpecialTransportContainer& etsi_its_cam_msgs::msg::SpecialVehicleContainer::special_transport_container() +{ + return m_special_transport_container; +} +/*! + * @brief This function copies the value in member dangerous_goods_container + * @param _dangerous_goods_container New value to be copied in member dangerous_goods_container + */ +void etsi_its_cam_msgs::msg::SpecialVehicleContainer::dangerous_goods_container( + const etsi_its_cam_msgs::msg::DangerousGoodsContainer& _dangerous_goods_container) +{ + m_dangerous_goods_container = _dangerous_goods_container; +} + +/*! + * @brief This function moves the value in member dangerous_goods_container + * @param _dangerous_goods_container New value to be moved in member dangerous_goods_container + */ +void etsi_its_cam_msgs::msg::SpecialVehicleContainer::dangerous_goods_container( + etsi_its_cam_msgs::msg::DangerousGoodsContainer&& _dangerous_goods_container) +{ + m_dangerous_goods_container = std::move(_dangerous_goods_container); +} + +/*! + * @brief This function returns a constant reference to member dangerous_goods_container + * @return Constant reference to member dangerous_goods_container + */ +const etsi_its_cam_msgs::msg::DangerousGoodsContainer& etsi_its_cam_msgs::msg::SpecialVehicleContainer::dangerous_goods_container() const +{ + return m_dangerous_goods_container; +} + +/*! + * @brief This function returns a reference to member dangerous_goods_container + * @return Reference to member dangerous_goods_container + */ +etsi_its_cam_msgs::msg::DangerousGoodsContainer& etsi_its_cam_msgs::msg::SpecialVehicleContainer::dangerous_goods_container() +{ + return m_dangerous_goods_container; +} +/*! + * @brief This function copies the value in member road_works_container_basic + * @param _road_works_container_basic New value to be copied in member road_works_container_basic + */ +void etsi_its_cam_msgs::msg::SpecialVehicleContainer::road_works_container_basic( + const etsi_its_cam_msgs::msg::RoadWorksContainerBasic& _road_works_container_basic) +{ + m_road_works_container_basic = _road_works_container_basic; +} + +/*! + * @brief This function moves the value in member road_works_container_basic + * @param _road_works_container_basic New value to be moved in member road_works_container_basic + */ +void etsi_its_cam_msgs::msg::SpecialVehicleContainer::road_works_container_basic( + etsi_its_cam_msgs::msg::RoadWorksContainerBasic&& _road_works_container_basic) +{ + m_road_works_container_basic = std::move(_road_works_container_basic); +} + +/*! + * @brief This function returns a constant reference to member road_works_container_basic + * @return Constant reference to member road_works_container_basic + */ +const etsi_its_cam_msgs::msg::RoadWorksContainerBasic& etsi_its_cam_msgs::msg::SpecialVehicleContainer::road_works_container_basic() const +{ + return m_road_works_container_basic; +} + +/*! + * @brief This function returns a reference to member road_works_container_basic + * @return Reference to member road_works_container_basic + */ +etsi_its_cam_msgs::msg::RoadWorksContainerBasic& etsi_its_cam_msgs::msg::SpecialVehicleContainer::road_works_container_basic() +{ + return m_road_works_container_basic; +} +/*! + * @brief This function copies the value in member rescue_container + * @param _rescue_container New value to be copied in member rescue_container + */ +void etsi_its_cam_msgs::msg::SpecialVehicleContainer::rescue_container( + const etsi_its_cam_msgs::msg::RescueContainer& _rescue_container) +{ + m_rescue_container = _rescue_container; +} + +/*! + * @brief This function moves the value in member rescue_container + * @param _rescue_container New value to be moved in member rescue_container + */ +void etsi_its_cam_msgs::msg::SpecialVehicleContainer::rescue_container( + etsi_its_cam_msgs::msg::RescueContainer&& _rescue_container) +{ + m_rescue_container = std::move(_rescue_container); +} + +/*! + * @brief This function returns a constant reference to member rescue_container + * @return Constant reference to member rescue_container + */ +const etsi_its_cam_msgs::msg::RescueContainer& etsi_its_cam_msgs::msg::SpecialVehicleContainer::rescue_container() const +{ + return m_rescue_container; +} + +/*! + * @brief This function returns a reference to member rescue_container + * @return Reference to member rescue_container + */ +etsi_its_cam_msgs::msg::RescueContainer& etsi_its_cam_msgs::msg::SpecialVehicleContainer::rescue_container() +{ + return m_rescue_container; +} +/*! + * @brief This function copies the value in member emergency_container + * @param _emergency_container New value to be copied in member emergency_container + */ +void etsi_its_cam_msgs::msg::SpecialVehicleContainer::emergency_container( + const etsi_its_cam_msgs::msg::EmergencyContainer& _emergency_container) +{ + m_emergency_container = _emergency_container; +} + +/*! + * @brief This function moves the value in member emergency_container + * @param _emergency_container New value to be moved in member emergency_container + */ +void etsi_its_cam_msgs::msg::SpecialVehicleContainer::emergency_container( + etsi_its_cam_msgs::msg::EmergencyContainer&& _emergency_container) +{ + m_emergency_container = std::move(_emergency_container); +} + +/*! + * @brief This function returns a constant reference to member emergency_container + * @return Constant reference to member emergency_container + */ +const etsi_its_cam_msgs::msg::EmergencyContainer& etsi_its_cam_msgs::msg::SpecialVehicleContainer::emergency_container() const +{ + return m_emergency_container; +} + +/*! + * @brief This function returns a reference to member emergency_container + * @return Reference to member emergency_container + */ +etsi_its_cam_msgs::msg::EmergencyContainer& etsi_its_cam_msgs::msg::SpecialVehicleContainer::emergency_container() +{ + return m_emergency_container; +} +/*! + * @brief This function copies the value in member safety_car_container + * @param _safety_car_container New value to be copied in member safety_car_container + */ +void etsi_its_cam_msgs::msg::SpecialVehicleContainer::safety_car_container( + const etsi_its_cam_msgs::msg::SafetyCarContainer& _safety_car_container) +{ + m_safety_car_container = _safety_car_container; +} + +/*! + * @brief This function moves the value in member safety_car_container + * @param _safety_car_container New value to be moved in member safety_car_container + */ +void etsi_its_cam_msgs::msg::SpecialVehicleContainer::safety_car_container( + etsi_its_cam_msgs::msg::SafetyCarContainer&& _safety_car_container) +{ + m_safety_car_container = std::move(_safety_car_container); +} + +/*! + * @brief This function returns a constant reference to member safety_car_container + * @return Constant reference to member safety_car_container + */ +const etsi_its_cam_msgs::msg::SafetyCarContainer& etsi_its_cam_msgs::msg::SpecialVehicleContainer::safety_car_container() const +{ + return m_safety_car_container; +} + +/*! + * @brief This function returns a reference to member safety_car_container + * @return Reference to member safety_car_container + */ +etsi_its_cam_msgs::msg::SafetyCarContainer& etsi_its_cam_msgs::msg::SpecialVehicleContainer::safety_car_container() +{ + return m_safety_car_container; +} + +size_t etsi_its_cam_msgs::msg::SpecialVehicleContainer::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::SpecialVehicleContainer::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::SpecialVehicleContainer::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainer.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainer.h new file mode 100644 index 00000000000..7b23d3d8275 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainer.h @@ -0,0 +1,408 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpecialVehicleContainer.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALVEHICLECONTAINER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALVEHICLECONTAINER_H_ + +#include "PublicTransportContainer.h" +#include "DangerousGoodsContainer.h" +#include "RescueContainer.h" +#include "EmergencyContainer.h" +#include "RoadWorksContainerBasic.h" +#include "SafetyCarContainer.h" +#include "SpecialTransportContainer.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(SpecialVehicleContainer_SOURCE) +#define SpecialVehicleContainer_DllAPI __declspec( dllexport ) +#else +#define SpecialVehicleContainer_DllAPI __declspec( dllimport ) +#endif // SpecialVehicleContainer_SOURCE +#else +#define SpecialVehicleContainer_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define SpecialVehicleContainer_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace SpecialVehicleContainer_Constants { + const uint8_t CHOICE_PUBLIC_TRANSPORT_CONTAINER = 0; + const uint8_t CHOICE_SPECIAL_TRANSPORT_CONTAINER = 1; + const uint8_t CHOICE_DANGEROUS_GOODS_CONTAINER = 2; + const uint8_t CHOICE_ROAD_WORKS_CONTAINER_BASIC = 3; + const uint8_t CHOICE_RESCUE_CONTAINER = 4; + const uint8_t CHOICE_EMERGENCY_CONTAINER = 5; + const uint8_t CHOICE_SAFETY_CAR_CONTAINER = 6; + } // namespace SpecialVehicleContainer_Constants + /*! + * @brief This class represents the structure SpecialVehicleContainer defined by the user in the IDL file. + * @ingroup SPECIALVEHICLECONTAINER + */ + class SpecialVehicleContainer + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport SpecialVehicleContainer(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~SpecialVehicleContainer(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpecialVehicleContainer that will be copied. + */ + eProsima_user_DllExport SpecialVehicleContainer( + const SpecialVehicleContainer& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpecialVehicleContainer that will be copied. + */ + eProsima_user_DllExport SpecialVehicleContainer( + SpecialVehicleContainer&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpecialVehicleContainer that will be copied. + */ + eProsima_user_DllExport SpecialVehicleContainer& operator =( + const SpecialVehicleContainer& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpecialVehicleContainer that will be copied. + */ + eProsima_user_DllExport SpecialVehicleContainer& operator =( + SpecialVehicleContainer&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SpecialVehicleContainer object to compare. + */ + eProsima_user_DllExport bool operator ==( + const SpecialVehicleContainer& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SpecialVehicleContainer object to compare. + */ + eProsima_user_DllExport bool operator !=( + const SpecialVehicleContainer& x) const; + + /*! + * @brief This function sets a value in member choice + * @param _choice New value for member choice + */ + eProsima_user_DllExport void choice( + uint8_t _choice); + + /*! + * @brief This function returns the value of member choice + * @return Value of member choice + */ + eProsima_user_DllExport uint8_t choice() const; + + /*! + * @brief This function returns a reference to member choice + * @return Reference to member choice + */ + eProsima_user_DllExport uint8_t& choice(); + + /*! + * @brief This function copies the value in member public_transport_container + * @param _public_transport_container New value to be copied in member public_transport_container + */ + eProsima_user_DllExport void public_transport_container( + const etsi_its_cam_msgs::msg::PublicTransportContainer& _public_transport_container); + + /*! + * @brief This function moves the value in member public_transport_container + * @param _public_transport_container New value to be moved in member public_transport_container + */ + eProsima_user_DllExport void public_transport_container( + etsi_its_cam_msgs::msg::PublicTransportContainer&& _public_transport_container); + + /*! + * @brief This function returns a constant reference to member public_transport_container + * @return Constant reference to member public_transport_container + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::PublicTransportContainer& public_transport_container() const; + + /*! + * @brief This function returns a reference to member public_transport_container + * @return Reference to member public_transport_container + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::PublicTransportContainer& public_transport_container(); + /*! + * @brief This function copies the value in member special_transport_container + * @param _special_transport_container New value to be copied in member special_transport_container + */ + eProsima_user_DllExport void special_transport_container( + const etsi_its_cam_msgs::msg::SpecialTransportContainer& _special_transport_container); + + /*! + * @brief This function moves the value in member special_transport_container + * @param _special_transport_container New value to be moved in member special_transport_container + */ + eProsima_user_DllExport void special_transport_container( + etsi_its_cam_msgs::msg::SpecialTransportContainer&& _special_transport_container); + + /*! + * @brief This function returns a constant reference to member special_transport_container + * @return Constant reference to member special_transport_container + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::SpecialTransportContainer& special_transport_container() const; + + /*! + * @brief This function returns a reference to member special_transport_container + * @return Reference to member special_transport_container + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::SpecialTransportContainer& special_transport_container(); + /*! + * @brief This function copies the value in member dangerous_goods_container + * @param _dangerous_goods_container New value to be copied in member dangerous_goods_container + */ + eProsima_user_DllExport void dangerous_goods_container( + const etsi_its_cam_msgs::msg::DangerousGoodsContainer& _dangerous_goods_container); + + /*! + * @brief This function moves the value in member dangerous_goods_container + * @param _dangerous_goods_container New value to be moved in member dangerous_goods_container + */ + eProsima_user_DllExport void dangerous_goods_container( + etsi_its_cam_msgs::msg::DangerousGoodsContainer&& _dangerous_goods_container); + + /*! + * @brief This function returns a constant reference to member dangerous_goods_container + * @return Constant reference to member dangerous_goods_container + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::DangerousGoodsContainer& dangerous_goods_container() const; + + /*! + * @brief This function returns a reference to member dangerous_goods_container + * @return Reference to member dangerous_goods_container + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::DangerousGoodsContainer& dangerous_goods_container(); + /*! + * @brief This function copies the value in member road_works_container_basic + * @param _road_works_container_basic New value to be copied in member road_works_container_basic + */ + eProsima_user_DllExport void road_works_container_basic( + const etsi_its_cam_msgs::msg::RoadWorksContainerBasic& _road_works_container_basic); + + /*! + * @brief This function moves the value in member road_works_container_basic + * @param _road_works_container_basic New value to be moved in member road_works_container_basic + */ + eProsima_user_DllExport void road_works_container_basic( + etsi_its_cam_msgs::msg::RoadWorksContainerBasic&& _road_works_container_basic); + + /*! + * @brief This function returns a constant reference to member road_works_container_basic + * @return Constant reference to member road_works_container_basic + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::RoadWorksContainerBasic& road_works_container_basic() const; + + /*! + * @brief This function returns a reference to member road_works_container_basic + * @return Reference to member road_works_container_basic + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::RoadWorksContainerBasic& road_works_container_basic(); + /*! + * @brief This function copies the value in member rescue_container + * @param _rescue_container New value to be copied in member rescue_container + */ + eProsima_user_DllExport void rescue_container( + const etsi_its_cam_msgs::msg::RescueContainer& _rescue_container); + + /*! + * @brief This function moves the value in member rescue_container + * @param _rescue_container New value to be moved in member rescue_container + */ + eProsima_user_DllExport void rescue_container( + etsi_its_cam_msgs::msg::RescueContainer&& _rescue_container); + + /*! + * @brief This function returns a constant reference to member rescue_container + * @return Constant reference to member rescue_container + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::RescueContainer& rescue_container() const; + + /*! + * @brief This function returns a reference to member rescue_container + * @return Reference to member rescue_container + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::RescueContainer& rescue_container(); + /*! + * @brief This function copies the value in member emergency_container + * @param _emergency_container New value to be copied in member emergency_container + */ + eProsima_user_DllExport void emergency_container( + const etsi_its_cam_msgs::msg::EmergencyContainer& _emergency_container); + + /*! + * @brief This function moves the value in member emergency_container + * @param _emergency_container New value to be moved in member emergency_container + */ + eProsima_user_DllExport void emergency_container( + etsi_its_cam_msgs::msg::EmergencyContainer&& _emergency_container); + + /*! + * @brief This function returns a constant reference to member emergency_container + * @return Constant reference to member emergency_container + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::EmergencyContainer& emergency_container() const; + + /*! + * @brief This function returns a reference to member emergency_container + * @return Reference to member emergency_container + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::EmergencyContainer& emergency_container(); + /*! + * @brief This function copies the value in member safety_car_container + * @param _safety_car_container New value to be copied in member safety_car_container + */ + eProsima_user_DllExport void safety_car_container( + const etsi_its_cam_msgs::msg::SafetyCarContainer& _safety_car_container); + + /*! + * @brief This function moves the value in member safety_car_container + * @param _safety_car_container New value to be moved in member safety_car_container + */ + eProsima_user_DllExport void safety_car_container( + etsi_its_cam_msgs::msg::SafetyCarContainer&& _safety_car_container); + + /*! + * @brief This function returns a constant reference to member safety_car_container + * @return Constant reference to member safety_car_container + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::SafetyCarContainer& safety_car_container() const; + + /*! + * @brief This function returns a reference to member safety_car_container + * @return Reference to member safety_car_container + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::SafetyCarContainer& safety_car_container(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SpecialVehicleContainer& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_choice; + etsi_its_cam_msgs::msg::PublicTransportContainer m_public_transport_container; + etsi_its_cam_msgs::msg::SpecialTransportContainer m_special_transport_container; + etsi_its_cam_msgs::msg::DangerousGoodsContainer m_dangerous_goods_container; + etsi_its_cam_msgs::msg::RoadWorksContainerBasic m_road_works_container_basic; + etsi_its_cam_msgs::msg::RescueContainer m_rescue_container; + etsi_its_cam_msgs::msg::EmergencyContainer m_emergency_container; + etsi_its_cam_msgs::msg::SafetyCarContainer m_safety_car_container; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALVEHICLECONTAINER_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainerPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainerPubSubTypes.cxx new file mode 100644 index 00000000000..c341e7ee7ef --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainerPubSubTypes.cxx @@ -0,0 +1,186 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpecialVehicleContainerPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "SpecialVehicleContainerPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace SpecialVehicleContainer_Constants { + + + + + + + + + } //End of namespace SpecialVehicleContainer_Constants + SpecialVehicleContainerPubSubType::SpecialVehicleContainerPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::SpecialVehicleContainer_"); + auto type_size = SpecialVehicleContainer::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = SpecialVehicleContainer::isKeyDefined(); + size_t keyLength = SpecialVehicleContainer::getKeyMaxCdrSerializedSize() > 16 ? + SpecialVehicleContainer::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + SpecialVehicleContainerPubSubType::~SpecialVehicleContainerPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool SpecialVehicleContainerPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + SpecialVehicleContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool SpecialVehicleContainerPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + SpecialVehicleContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function SpecialVehicleContainerPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* SpecialVehicleContainerPubSubType::createData() + { + return reinterpret_cast(new SpecialVehicleContainer()); + } + + void SpecialVehicleContainerPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool SpecialVehicleContainerPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + SpecialVehicleContainer* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + SpecialVehicleContainer::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || SpecialVehicleContainer::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainerPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainerPubSubTypes.h new file mode 100644 index 00000000000..b46bee1df9b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainerPubSubTypes.h @@ -0,0 +1,117 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpecialVehicleContainerPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALVEHICLECONTAINER_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALVEHICLECONTAINER_PUBSUBTYPES_H_ + +#include +#include + +#include "SpecialVehicleContainer.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated SpecialVehicleContainer is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace SpecialVehicleContainer_Constants + { + + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type SpecialVehicleContainer defined by the user in the IDL file. + * @ingroup SPECIALVEHICLECONTAINER + */ + class SpecialVehicleContainerPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef SpecialVehicleContainer type; + + eProsima_user_DllExport SpecialVehicleContainerPubSubType(); + + eProsima_user_DllExport virtual ~SpecialVehicleContainerPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + (void)memory; + return false; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALVEHICLECONTAINER_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Speed.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Speed.cxx new file mode 100644 index 00000000000..a7a292e82d2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Speed.cxx @@ -0,0 +1,238 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Speed.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Speed.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::Speed::Speed() +{ + // m_speed_value com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@1d3e6d34 + + // m_speed_confidence com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@6eafb10e + + +} + +etsi_its_cam_msgs::msg::Speed::~Speed() +{ + +} + +etsi_its_cam_msgs::msg::Speed::Speed( + const Speed& x) +{ + m_speed_value = x.m_speed_value; + m_speed_confidence = x.m_speed_confidence; +} + +etsi_its_cam_msgs::msg::Speed::Speed( + Speed&& x) +{ + m_speed_value = std::move(x.m_speed_value); + m_speed_confidence = std::move(x.m_speed_confidence); +} + +etsi_its_cam_msgs::msg::Speed& etsi_its_cam_msgs::msg::Speed::operator =( + const Speed& x) +{ + + m_speed_value = x.m_speed_value; + m_speed_confidence = x.m_speed_confidence; + + return *this; +} + +etsi_its_cam_msgs::msg::Speed& etsi_its_cam_msgs::msg::Speed::operator =( + Speed&& x) +{ + + m_speed_value = std::move(x.m_speed_value); + m_speed_confidence = std::move(x.m_speed_confidence); + + return *this; +} + +bool etsi_its_cam_msgs::msg::Speed::operator ==( + const Speed& x) const +{ + + return (m_speed_value == x.m_speed_value && m_speed_confidence == x.m_speed_confidence); +} + +bool etsi_its_cam_msgs::msg::Speed::operator !=( + const Speed& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::Speed::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::SpeedValue::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::SpeedConfidence::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::Speed::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::Speed& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::SpeedValue::getCdrSerializedSize(data.speed_value(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::SpeedConfidence::getCdrSerializedSize(data.speed_confidence(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::Speed::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_speed_value; + scdr << m_speed_confidence; + +} + +void etsi_its_cam_msgs::msg::Speed::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_speed_value; + dcdr >> m_speed_confidence; +} + +/*! + * @brief This function copies the value in member speed_value + * @param _speed_value New value to be copied in member speed_value + */ +void etsi_its_cam_msgs::msg::Speed::speed_value( + const etsi_its_cam_msgs::msg::SpeedValue& _speed_value) +{ + m_speed_value = _speed_value; +} + +/*! + * @brief This function moves the value in member speed_value + * @param _speed_value New value to be moved in member speed_value + */ +void etsi_its_cam_msgs::msg::Speed::speed_value( + etsi_its_cam_msgs::msg::SpeedValue&& _speed_value) +{ + m_speed_value = std::move(_speed_value); +} + +/*! + * @brief This function returns a constant reference to member speed_value + * @return Constant reference to member speed_value + */ +const etsi_its_cam_msgs::msg::SpeedValue& etsi_its_cam_msgs::msg::Speed::speed_value() const +{ + return m_speed_value; +} + +/*! + * @brief This function returns a reference to member speed_value + * @return Reference to member speed_value + */ +etsi_its_cam_msgs::msg::SpeedValue& etsi_its_cam_msgs::msg::Speed::speed_value() +{ + return m_speed_value; +} +/*! + * @brief This function copies the value in member speed_confidence + * @param _speed_confidence New value to be copied in member speed_confidence + */ +void etsi_its_cam_msgs::msg::Speed::speed_confidence( + const etsi_its_cam_msgs::msg::SpeedConfidence& _speed_confidence) +{ + m_speed_confidence = _speed_confidence; +} + +/*! + * @brief This function moves the value in member speed_confidence + * @param _speed_confidence New value to be moved in member speed_confidence + */ +void etsi_its_cam_msgs::msg::Speed::speed_confidence( + etsi_its_cam_msgs::msg::SpeedConfidence&& _speed_confidence) +{ + m_speed_confidence = std::move(_speed_confidence); +} + +/*! + * @brief This function returns a constant reference to member speed_confidence + * @return Constant reference to member speed_confidence + */ +const etsi_its_cam_msgs::msg::SpeedConfidence& etsi_its_cam_msgs::msg::Speed::speed_confidence() const +{ + return m_speed_confidence; +} + +/*! + * @brief This function returns a reference to member speed_confidence + * @return Reference to member speed_confidence + */ +etsi_its_cam_msgs::msg::SpeedConfidence& etsi_its_cam_msgs::msg::Speed::speed_confidence() +{ + return m_speed_confidence; +} + +size_t etsi_its_cam_msgs::msg::Speed::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::Speed::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::Speed::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Speed.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Speed.h new file mode 100644 index 00000000000..53db960580c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Speed.h @@ -0,0 +1,244 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Speed.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEED_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEED_H_ + +#include "SpeedValue.h" +#include "SpeedConfidence.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(Speed_SOURCE) +#define Speed_DllAPI __declspec( dllexport ) +#else +#define Speed_DllAPI __declspec( dllimport ) +#endif // Speed_SOURCE +#else +#define Speed_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define Speed_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure Speed defined by the user in the IDL file. + * @ingroup SPEED + */ + class Speed + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Speed(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Speed(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::Speed that will be copied. + */ + eProsima_user_DllExport Speed( + const Speed& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::Speed that will be copied. + */ + eProsima_user_DllExport Speed( + Speed&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::Speed that will be copied. + */ + eProsima_user_DllExport Speed& operator =( + const Speed& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::Speed that will be copied. + */ + eProsima_user_DllExport Speed& operator =( + Speed&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::Speed object to compare. + */ + eProsima_user_DllExport bool operator ==( + const Speed& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::Speed object to compare. + */ + eProsima_user_DllExport bool operator !=( + const Speed& x) const; + + /*! + * @brief This function copies the value in member speed_value + * @param _speed_value New value to be copied in member speed_value + */ + eProsima_user_DllExport void speed_value( + const etsi_its_cam_msgs::msg::SpeedValue& _speed_value); + + /*! + * @brief This function moves the value in member speed_value + * @param _speed_value New value to be moved in member speed_value + */ + eProsima_user_DllExport void speed_value( + etsi_its_cam_msgs::msg::SpeedValue&& _speed_value); + + /*! + * @brief This function returns a constant reference to member speed_value + * @return Constant reference to member speed_value + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::SpeedValue& speed_value() const; + + /*! + * @brief This function returns a reference to member speed_value + * @return Reference to member speed_value + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::SpeedValue& speed_value(); + /*! + * @brief This function copies the value in member speed_confidence + * @param _speed_confidence New value to be copied in member speed_confidence + */ + eProsima_user_DllExport void speed_confidence( + const etsi_its_cam_msgs::msg::SpeedConfidence& _speed_confidence); + + /*! + * @brief This function moves the value in member speed_confidence + * @param _speed_confidence New value to be moved in member speed_confidence + */ + eProsima_user_DllExport void speed_confidence( + etsi_its_cam_msgs::msg::SpeedConfidence&& _speed_confidence); + + /*! + * @brief This function returns a constant reference to member speed_confidence + * @return Constant reference to member speed_confidence + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::SpeedConfidence& speed_confidence() const; + + /*! + * @brief This function returns a reference to member speed_confidence + * @return Reference to member speed_confidence + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::SpeedConfidence& speed_confidence(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::Speed& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::SpeedValue m_speed_value; + etsi_its_cam_msgs::msg::SpeedConfidence m_speed_confidence; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEED_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidence.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidence.cxx new file mode 100644 index 00000000000..936602ff0d3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidence.cxx @@ -0,0 +1,190 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpeedConfidence.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "SpeedConfidence.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + +etsi_its_cam_msgs::msg::SpeedConfidence::SpeedConfidence() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@bcb09a6 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::SpeedConfidence::~SpeedConfidence() +{ +} + +etsi_its_cam_msgs::msg::SpeedConfidence::SpeedConfidence( + const SpeedConfidence& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::SpeedConfidence::SpeedConfidence( + SpeedConfidence&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::SpeedConfidence& etsi_its_cam_msgs::msg::SpeedConfidence::operator =( + const SpeedConfidence& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::SpeedConfidence& etsi_its_cam_msgs::msg::SpeedConfidence::operator =( + SpeedConfidence&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::SpeedConfidence::operator ==( + const SpeedConfidence& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::SpeedConfidence::operator !=( + const SpeedConfidence& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::SpeedConfidence::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::SpeedConfidence::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SpeedConfidence& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::SpeedConfidence::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::SpeedConfidence::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::SpeedConfidence::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::SpeedConfidence::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::SpeedConfidence::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::SpeedConfidence::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::SpeedConfidence::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::SpeedConfidence::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidence.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidence.h new file mode 100644 index 00000000000..1f88c66aecf --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidence.h @@ -0,0 +1,218 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpeedConfidence.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDCONFIDENCE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDCONFIDENCE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(SpeedConfidence_SOURCE) +#define SpeedConfidence_DllAPI __declspec( dllexport ) +#else +#define SpeedConfidence_DllAPI __declspec( dllimport ) +#endif // SpeedConfidence_SOURCE +#else +#define SpeedConfidence_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define SpeedConfidence_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace SpeedConfidence_Constants { + const uint8_t MIN = 1; + const uint8_t MAX = 127; + const uint8_t EQUAL_OR_WITHIN_ONE_CENTIMETER_PER_SEC = 1; + const uint8_t EQUAL_OR_WITHIN_ONE_METER_PER_SEC = 100; + const uint8_t OUT_OF_RANGE = 126; + const uint8_t UNAVAILABLE = 127; + } // namespace SpeedConfidence_Constants + /*! + * @brief This class represents the structure SpeedConfidence defined by the user in the IDL file. + * @ingroup SPEEDCONFIDENCE + */ + class SpeedConfidence + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport SpeedConfidence(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~SpeedConfidence(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpeedConfidence that will be copied. + */ + eProsima_user_DllExport SpeedConfidence( + const SpeedConfidence& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpeedConfidence that will be copied. + */ + eProsima_user_DllExport SpeedConfidence( + SpeedConfidence&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpeedConfidence that will be copied. + */ + eProsima_user_DllExport SpeedConfidence& operator =( + const SpeedConfidence& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpeedConfidence that will be copied. + */ + eProsima_user_DllExport SpeedConfidence& operator =( + SpeedConfidence&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SpeedConfidence object to compare. + */ + eProsima_user_DllExport bool operator ==( + const SpeedConfidence& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SpeedConfidence object to compare. + */ + eProsima_user_DllExport bool operator !=( + const SpeedConfidence& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SpeedConfidence& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDCONFIDENCE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidencePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidencePubSubTypes.cxx new file mode 100644 index 00000000000..117c751390b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidencePubSubTypes.cxx @@ -0,0 +1,185 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpeedConfidencePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "SpeedConfidencePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace SpeedConfidence_Constants { + + + + + + + + } //End of namespace SpeedConfidence_Constants + SpeedConfidencePubSubType::SpeedConfidencePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::SpeedConfidence_"); + auto type_size = SpeedConfidence::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = SpeedConfidence::isKeyDefined(); + size_t keyLength = SpeedConfidence::getKeyMaxCdrSerializedSize() > 16 ? + SpeedConfidence::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + SpeedConfidencePubSubType::~SpeedConfidencePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool SpeedConfidencePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + SpeedConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool SpeedConfidencePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + SpeedConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function SpeedConfidencePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* SpeedConfidencePubSubType::createData() + { + return reinterpret_cast(new SpeedConfidence()); + } + + void SpeedConfidencePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool SpeedConfidencePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + SpeedConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + SpeedConfidence::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || SpeedConfidence::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidencePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidencePubSubTypes.h new file mode 100644 index 00000000000..0590ba645fd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidencePubSubTypes.h @@ -0,0 +1,116 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpeedConfidencePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDCONFIDENCE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDCONFIDENCE_PUBSUBTYPES_H_ + +#include +#include + +#include "SpeedConfidence.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated SpeedConfidence is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace SpeedConfidence_Constants + { + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type SpeedConfidence defined by the user in the IDL file. + * @ingroup SPEEDCONFIDENCE + */ + class SpeedConfidencePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef SpeedConfidence type; + + eProsima_user_DllExport SpeedConfidencePubSubType(); + + eProsima_user_DllExport virtual ~SpeedConfidencePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) SpeedConfidence(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDCONFIDENCE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimit.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimit.cxx new file mode 100644 index 00000000000..da0805886c4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimit.cxx @@ -0,0 +1,187 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpeedLimit.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "SpeedLimit.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + +etsi_its_cam_msgs::msg::SpeedLimit::SpeedLimit() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@7fd4acee + m_value = 0; + +} + +etsi_its_cam_msgs::msg::SpeedLimit::~SpeedLimit() +{ +} + +etsi_its_cam_msgs::msg::SpeedLimit::SpeedLimit( + const SpeedLimit& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::SpeedLimit::SpeedLimit( + SpeedLimit&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::SpeedLimit& etsi_its_cam_msgs::msg::SpeedLimit::operator =( + const SpeedLimit& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::SpeedLimit& etsi_its_cam_msgs::msg::SpeedLimit::operator =( + SpeedLimit&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::SpeedLimit::operator ==( + const SpeedLimit& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::SpeedLimit::operator !=( + const SpeedLimit& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::SpeedLimit::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::SpeedLimit::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SpeedLimit& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::SpeedLimit::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::SpeedLimit::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::SpeedLimit::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::SpeedLimit::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::SpeedLimit::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::SpeedLimit::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::SpeedLimit::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::SpeedLimit::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimit.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimit.h new file mode 100644 index 00000000000..4ec5893b373 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimit.h @@ -0,0 +1,215 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpeedLimit.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDLIMIT_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDLIMIT_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(SpeedLimit_SOURCE) +#define SpeedLimit_DllAPI __declspec( dllexport ) +#else +#define SpeedLimit_DllAPI __declspec( dllimport ) +#endif // SpeedLimit_SOURCE +#else +#define SpeedLimit_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define SpeedLimit_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace SpeedLimit_Constants { + const uint8_t MIN = 1; + const uint8_t MAX = 255; + const uint8_t ONE_KM_PER_HOUR = 1; + } // namespace SpeedLimit_Constants + /*! + * @brief This class represents the structure SpeedLimit defined by the user in the IDL file. + * @ingroup SPEEDLIMIT + */ + class SpeedLimit + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport SpeedLimit(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~SpeedLimit(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpeedLimit that will be copied. + */ + eProsima_user_DllExport SpeedLimit( + const SpeedLimit& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpeedLimit that will be copied. + */ + eProsima_user_DllExport SpeedLimit( + SpeedLimit&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpeedLimit that will be copied. + */ + eProsima_user_DllExport SpeedLimit& operator =( + const SpeedLimit& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpeedLimit that will be copied. + */ + eProsima_user_DllExport SpeedLimit& operator =( + SpeedLimit&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SpeedLimit object to compare. + */ + eProsima_user_DllExport bool operator ==( + const SpeedLimit& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SpeedLimit object to compare. + */ + eProsima_user_DllExport bool operator !=( + const SpeedLimit& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SpeedLimit& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDLIMIT_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimitPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimitPubSubTypes.cxx new file mode 100644 index 00000000000..643f1e77dd1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimitPubSubTypes.cxx @@ -0,0 +1,182 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpeedLimitPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "SpeedLimitPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace SpeedLimit_Constants { + + + + + } //End of namespace SpeedLimit_Constants + SpeedLimitPubSubType::SpeedLimitPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::SpeedLimit_"); + auto type_size = SpeedLimit::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = SpeedLimit::isKeyDefined(); + size_t keyLength = SpeedLimit::getKeyMaxCdrSerializedSize() > 16 ? + SpeedLimit::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + SpeedLimitPubSubType::~SpeedLimitPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool SpeedLimitPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + SpeedLimit* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool SpeedLimitPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + SpeedLimit* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function SpeedLimitPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* SpeedLimitPubSubType::createData() + { + return reinterpret_cast(new SpeedLimit()); + } + + void SpeedLimitPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool SpeedLimitPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + SpeedLimit* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + SpeedLimit::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || SpeedLimit::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/types/CameraInfoPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimitPubSubTypes.h similarity index 75% rename from LibCarla/source/carla/ros2/types/CameraInfoPubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimitPubSubTypes.h index fe7764ab98e..4e22177920d 100644 --- a/LibCarla/source/carla/ros2/types/CameraInfoPubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimitPubSubTypes.h @@ -13,45 +13,49 @@ // limitations under the License. /*! - * @file CameraInfoPubSubTypes.h + * @file SpeedLimitPubSubTypes.h * This header file contains the declaration of the serialization functions. * * This file was generated by the tool fastcdrgen. */ -#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFO_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFO_PUBSUBTYPES_H_ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDLIMIT_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDLIMIT_PUBSUBTYPES_H_ #include #include -#include "CameraInfo.h" - -#include "RegionOfInterestPubSubTypes.h" -#include "HeaderPubSubTypes.h" +#include "SpeedLimit.h" #if !defined(GEN_API_VER) || (GEN_API_VER != 1) #error \ - Generated CameraInfo is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. + Generated SpeedLimit is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. #endif // GEN_API_VER -namespace sensor_msgs +namespace etsi_its_cam_msgs { namespace msg { + namespace SpeedLimit_Constants + { + + + + } /*! - * @brief This class represents the TopicDataType of the type CameraInfo defined by the user in the IDL file. - * @ingroup CameraInfo + * @brief This class represents the TopicDataType of the type SpeedLimit defined by the user in the IDL file. + * @ingroup SPEEDLIMIT */ - class CameraInfoPubSubType : public eprosima::fastdds::dds::TopicDataType + class SpeedLimitPubSubType : public eprosima::fastdds::dds::TopicDataType { public: - typedef CameraInfo type; + typedef SpeedLimit type; - eProsima_user_DllExport CameraInfoPubSubType(); + eProsima_user_DllExport SpeedLimitPubSubType(); - eProsima_user_DllExport virtual ~CameraInfoPubSubType() override; + eProsima_user_DllExport virtual ~SpeedLimitPubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -77,7 +81,7 @@ namespace sensor_msgs #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED eProsima_user_DllExport inline bool is_bounded() const override { - return false; + return true; } #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED @@ -85,7 +89,7 @@ namespace sensor_msgs #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN eProsima_user_DllExport inline bool is_plain() const override { - return false; + return true; } #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN @@ -94,15 +98,16 @@ namespace sensor_msgs eProsima_user_DllExport inline bool construct_sample( void* memory) const override { - (void)memory; - return false; + new (memory) SpeedLimit(); + return true; } #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; unsigned char* m_keyBuffer; }; } } -#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFO_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDLIMIT_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedPubSubTypes.cxx new file mode 100644 index 00000000000..2dc44d40b17 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpeedPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "SpeedPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + SpeedPubSubType::SpeedPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::Speed_"); + auto type_size = Speed::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = Speed::isKeyDefined(); + size_t keyLength = Speed::getKeyMaxCdrSerializedSize() > 16 ? + Speed::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + SpeedPubSubType::~SpeedPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool SpeedPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + Speed* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool SpeedPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + Speed* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function SpeedPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* SpeedPubSubType::createData() + { + return reinterpret_cast(new Speed()); + } + + void SpeedPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool SpeedPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + Speed* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + Speed::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || Speed::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedPubSubTypes.h new file mode 100644 index 00000000000..14bab114d7e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpeedPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEED_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEED_PUBSUBTYPES_H_ + +#include +#include + +#include "Speed.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated Speed is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type Speed defined by the user in the IDL file. + * @ingroup SPEED + */ + class SpeedPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef Speed type; + + eProsima_user_DllExport SpeedPubSubType(); + + eProsima_user_DllExport virtual ~SpeedPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) Speed(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEED_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValue.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValue.cxx new file mode 100644 index 00000000000..a1fbb345de5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValue.cxx @@ -0,0 +1,189 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpeedValue.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "SpeedValue.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + +etsi_its_cam_msgs::msg::SpeedValue::SpeedValue() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@41477a6d + m_value = 0; + +} + +etsi_its_cam_msgs::msg::SpeedValue::~SpeedValue() +{ +} + +etsi_its_cam_msgs::msg::SpeedValue::SpeedValue( + const SpeedValue& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::SpeedValue::SpeedValue( + SpeedValue&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::SpeedValue& etsi_its_cam_msgs::msg::SpeedValue::operator =( + const SpeedValue& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::SpeedValue& etsi_its_cam_msgs::msg::SpeedValue::operator =( + SpeedValue&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::SpeedValue::operator ==( + const SpeedValue& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::SpeedValue::operator !=( + const SpeedValue& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::SpeedValue::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::SpeedValue::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SpeedValue& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::SpeedValue::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::SpeedValue::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::SpeedValue::value( + uint16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint16_t etsi_its_cam_msgs::msg::SpeedValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint16_t& etsi_its_cam_msgs::msg::SpeedValue::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::SpeedValue::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::SpeedValue::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::SpeedValue::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValue.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValue.h new file mode 100644 index 00000000000..34951129a8d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValue.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpeedValue.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDVALUE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDVALUE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(SpeedValue_SOURCE) +#define SpeedValue_DllAPI __declspec( dllexport ) +#else +#define SpeedValue_DllAPI __declspec( dllimport ) +#endif // SpeedValue_SOURCE +#else +#define SpeedValue_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define SpeedValue_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace SpeedValue_Constants { + const uint16_t MIN = 0; + const uint16_t MAX = 16383; + const uint16_t STANDSTILL = 0; + const uint16_t ONE_CENTIMETER_PER_SEC = 1; + const uint16_t UNAVAILABLE = 16383; + } // namespace SpeedValue_Constants + /*! + * @brief This class represents the structure SpeedValue defined by the user in the IDL file. + * @ingroup SPEEDVALUE + */ + class SpeedValue + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport SpeedValue(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~SpeedValue(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpeedValue that will be copied. + */ + eProsima_user_DllExport SpeedValue( + const SpeedValue& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpeedValue that will be copied. + */ + eProsima_user_DllExport SpeedValue( + SpeedValue&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpeedValue that will be copied. + */ + eProsima_user_DllExport SpeedValue& operator =( + const SpeedValue& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SpeedValue that will be copied. + */ + eProsima_user_DllExport SpeedValue& operator =( + SpeedValue&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SpeedValue object to compare. + */ + eProsima_user_DllExport bool operator ==( + const SpeedValue& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SpeedValue object to compare. + */ + eProsima_user_DllExport bool operator !=( + const SpeedValue& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint16_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint16_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint16_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SpeedValue& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint16_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDVALUE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValuePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValuePubSubTypes.cxx new file mode 100644 index 00000000000..13b08fc8e7e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValuePubSubTypes.cxx @@ -0,0 +1,184 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpeedValuePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "SpeedValuePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace SpeedValue_Constants { + + + + + + + } //End of namespace SpeedValue_Constants + SpeedValuePubSubType::SpeedValuePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::SpeedValue_"); + auto type_size = SpeedValue::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = SpeedValue::isKeyDefined(); + size_t keyLength = SpeedValue::getKeyMaxCdrSerializedSize() > 16 ? + SpeedValue::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + SpeedValuePubSubType::~SpeedValuePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool SpeedValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + SpeedValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool SpeedValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + SpeedValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function SpeedValuePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* SpeedValuePubSubType::createData() + { + return reinterpret_cast(new SpeedValue()); + } + + void SpeedValuePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool SpeedValuePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + SpeedValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + SpeedValue::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || SpeedValue::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValuePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValuePubSubTypes.h new file mode 100644 index 00000000000..9d5ee7fb807 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValuePubSubTypes.h @@ -0,0 +1,115 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SpeedValuePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDVALUE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDVALUE_PUBSUBTYPES_H_ + +#include +#include + +#include "SpeedValue.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated SpeedValue is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace SpeedValue_Constants + { + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type SpeedValue defined by the user in the IDL file. + * @ingroup SPEEDVALUE + */ + class SpeedValuePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef SpeedValue type; + + eProsima_user_DllExport SpeedValuePubSubType(); + + eProsima_user_DllExport virtual ~SpeedValuePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) SpeedValue(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDVALUE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationID.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationID.cxx new file mode 100644 index 00000000000..1aacaed0d10 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationID.cxx @@ -0,0 +1,186 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file StationID.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "StationID.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + +etsi_its_cam_msgs::msg::StationID::StationID() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@6e6d5d29 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::StationID::~StationID() +{ +} + +etsi_its_cam_msgs::msg::StationID::StationID( + const StationID& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::StationID::StationID( + StationID&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::StationID& etsi_its_cam_msgs::msg::StationID::operator =( + const StationID& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::StationID& etsi_its_cam_msgs::msg::StationID::operator =( + StationID&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::StationID::operator ==( + const StationID& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::StationID::operator !=( + const StationID& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::StationID::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::StationID::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::StationID& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::StationID::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::StationID::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::StationID::value( + uint32_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint32_t etsi_its_cam_msgs::msg::StationID::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint32_t& etsi_its_cam_msgs::msg::StationID::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::StationID::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::StationID::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::StationID::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/types/Float32.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationID.h similarity index 62% rename from LibCarla/source/carla/ros2/types/Float32.h rename to LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationID.h index e857e2c10a3..101b07253f0 100644 --- a/LibCarla/source/carla/ros2/types/Float32.h +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationID.h @@ -13,16 +13,15 @@ // limitations under the License. /*! - * @file Float32.h + * @file StationID.h * This header file contains the declaration of the described types in the IDL file. * * This file was generated by the tool gen. */ -#ifndef _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32_H_ -#define _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32_H_ +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONID_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONID_H_ -#include #include #include @@ -43,16 +42,16 @@ #if defined(_WIN32) #if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(Float32_SOURCE) -#define Float32_DllAPI __declspec( dllexport ) +#if defined(StationID_SOURCE) +#define StationID_DllAPI __declspec( dllexport ) #else -#define Float32_DllAPI __declspec( dllimport ) -#endif // Float32_SOURCE +#define StationID_DllAPI __declspec( dllimport ) +#endif // StationID_SOURCE #else -#define Float32_DllAPI +#define StationID_DllAPI #endif // EPROSIMA_USER_DLL_EXPORT #else -#define Float32_DllAPI +#define StationID_DllAPI #endif // _WIN32 namespace eprosima { @@ -61,92 +60,99 @@ class Cdr; } // namespace fastcdr } // namespace eprosima -namespace std_msgs { + +namespace etsi_its_cam_msgs { namespace msg { + namespace StationID_Constants { + const uint32_t MIN = 0; + const uint32_t MAX = 4294967295; + } // namespace StationID_Constants /*! - * @brief This class represents the structure Float32 defined by the user in the IDL file. - * @ingroup FLOAT32 + * @brief This class represents the structure StationID defined by the user in the IDL file. + * @ingroup STATIONID */ - class Float32 + class StationID { public: + /*! * @brief Default constructor. */ - eProsima_user_DllExport Float32(); + eProsima_user_DllExport StationID(); /*! * @brief Default destructor. */ - eProsima_user_DllExport ~Float32(); + eProsima_user_DllExport ~StationID(); /*! * @brief Copy constructor. - * @param x Reference to the object std_msgs::msg::Float32 that will be copied. + * @param x Reference to the object etsi_its_cam_msgs::msg::StationID that will be copied. */ - eProsima_user_DllExport Float32( - const Float32& x); + eProsima_user_DllExport StationID( + const StationID& x); /*! * @brief Move constructor. - * @param x Reference to the object std_msgs::msg::Float32 that will be copied. + * @param x Reference to the object etsi_its_cam_msgs::msg::StationID that will be copied. */ - eProsima_user_DllExport Float32( - Float32&& x) noexcept; + eProsima_user_DllExport StationID( + StationID&& x); /*! * @brief Copy assignment. - * @param x Reference to the object std_msgs::msg::Float32 that will be copied. + * @param x Reference to the object etsi_its_cam_msgs::msg::StationID that will be copied. */ - eProsima_user_DllExport Float32& operator =( - const Float32& x); + eProsima_user_DllExport StationID& operator =( + const StationID& x); /*! * @brief Move assignment. - * @param x Reference to the object std_msgs::msg::Float32 that will be copied. + * @param x Reference to the object etsi_its_cam_msgs::msg::StationID that will be copied. */ - eProsima_user_DllExport Float32& operator =( - Float32&& x) noexcept; + eProsima_user_DllExport StationID& operator =( + StationID&& x); /*! * @brief Comparison operator. - * @param x std_msgs::msg::Float32 object to compare. + * @param x etsi_its_cam_msgs::msg::StationID object to compare. */ eProsima_user_DllExport bool operator ==( - const Float32& x) const; + const StationID& x) const; /*! * @brief Comparison operator. - * @param x std_msgs::msg::Float32 object to compare. + * @param x etsi_its_cam_msgs::msg::StationID object to compare. */ eProsima_user_DllExport bool operator !=( - const Float32& x) const; + const StationID& x) const; /*! - * @brief This function sets a value in member data - * @param _data New value for member data + * @brief This function sets a value in member value + * @param _value New value for member value */ - eProsima_user_DllExport void data( - float _data); + eProsima_user_DllExport void value( + uint32_t _value); /*! - * @brief This function returns the value of member data - * @return Value of member data + * @brief This function returns the value of member value + * @return Value of member value */ - eProsima_user_DllExport float data() const; + eProsima_user_DllExport uint32_t value() const; /*! - * @brief This function returns a reference to member data - * @return Reference to member data + * @brief This function returns a reference to member value + * @return Reference to member value */ - eProsima_user_DllExport float& data(); + eProsima_user_DllExport uint32_t& value(); + /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -157,9 +163,10 @@ namespace std_msgs { * @return Serialized size. */ eProsima_user_DllExport static size_t getCdrSerializedSize( - const std_msgs::msg::Float32& data, + const etsi_its_cam_msgs::msg::StationID& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -174,6 +181,8 @@ namespace std_msgs { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -196,9 +205,10 @@ namespace std_msgs { eprosima::fastcdr::Cdr& cdr) const; private: - float m_data; + + uint32_t m_value; }; } // namespace msg -} // namespace std_msgs +} // namespace etsi_its_cam_msgs -#endif // _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32_H_ +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONID_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationIDPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationIDPubSubTypes.cxx new file mode 100644 index 00000000000..d501c2176e5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationIDPubSubTypes.cxx @@ -0,0 +1,181 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file StationIDPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "StationIDPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace StationID_Constants { + + + + } //End of namespace StationID_Constants + StationIDPubSubType::StationIDPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::StationID_"); + auto type_size = StationID::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = StationID::isKeyDefined(); + size_t keyLength = StationID::getKeyMaxCdrSerializedSize() > 16 ? + StationID::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + StationIDPubSubType::~StationIDPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool StationIDPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + StationID* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool StationIDPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + StationID* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function StationIDPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* StationIDPubSubType::createData() + { + return reinterpret_cast(new StationID()); + } + + void StationIDPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool StationIDPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + StationID* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + StationID::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || StationID::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationIDPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationIDPubSubTypes.h new file mode 100644 index 00000000000..90a59a096d4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationIDPubSubTypes.h @@ -0,0 +1,112 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file StationIDPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONID_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONID_PUBSUBTYPES_H_ + +#include +#include + +#include "StationID.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated StationID is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace StationID_Constants + { + + + } + /*! + * @brief This class represents the TopicDataType of the type StationID defined by the user in the IDL file. + * @ingroup STATIONID + */ + class StationIDPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef StationID type; + + eProsima_user_DllExport StationIDPubSubType(); + + eProsima_user_DllExport virtual ~StationIDPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) StationID(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONID_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationType.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationType.cxx new file mode 100644 index 00000000000..ada976c13a0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationType.cxx @@ -0,0 +1,199 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file StationType.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "StationType.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + + + + + + + + + + +etsi_its_cam_msgs::msg::StationType::StationType() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@4632cfc + m_value = 0; + +} + +etsi_its_cam_msgs::msg::StationType::~StationType() +{ +} + +etsi_its_cam_msgs::msg::StationType::StationType( + const StationType& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::StationType::StationType( + StationType&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::StationType& etsi_its_cam_msgs::msg::StationType::operator =( + const StationType& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::StationType& etsi_its_cam_msgs::msg::StationType::operator =( + StationType&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::StationType::operator ==( + const StationType& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::StationType::operator !=( + const StationType& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::StationType::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::StationType::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::StationType& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::StationType::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::StationType::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::StationType::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::StationType::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::StationType::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::StationType::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::StationType::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::StationType::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationType.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationType.h new file mode 100644 index 00000000000..05d0439663e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationType.h @@ -0,0 +1,227 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file StationType.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONTYPE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONTYPE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(StationType_SOURCE) +#define StationType_DllAPI __declspec( dllexport ) +#else +#define StationType_DllAPI __declspec( dllimport ) +#endif // StationType_SOURCE +#else +#define StationType_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define StationType_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace StationType_Constants { + const uint8_t MIN = 0; + const uint8_t MAX = 255; + const uint8_t UNKNOWN = 0; + const uint8_t PEDESTRIAN = 1; + const uint8_t CYCLIST = 2; + const uint8_t MOPED = 3; + const uint8_t MOTORCYCLE = 4; + const uint8_t PASSENGER_CAR = 5; + const uint8_t BUS = 6; + const uint8_t LIGHT_TRUCK = 7; + const uint8_t HEAVY_TRUCK = 8; + const uint8_t TRAILER = 9; + const uint8_t SPECIAL_VEHICLES = 10; + const uint8_t TRAM = 11; + const uint8_t ROAD_SIDE_UNIT = 15; + } // namespace StationType_Constants + /*! + * @brief This class represents the structure StationType defined by the user in the IDL file. + * @ingroup STATIONTYPE + */ + class StationType + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport StationType(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~StationType(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::StationType that will be copied. + */ + eProsima_user_DllExport StationType( + const StationType& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::StationType that will be copied. + */ + eProsima_user_DllExport StationType( + StationType&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::StationType that will be copied. + */ + eProsima_user_DllExport StationType& operator =( + const StationType& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::StationType that will be copied. + */ + eProsima_user_DllExport StationType& operator =( + StationType&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::StationType object to compare. + */ + eProsima_user_DllExport bool operator ==( + const StationType& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::StationType object to compare. + */ + eProsima_user_DllExport bool operator !=( + const StationType& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::StationType& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONTYPE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationTypePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationTypePubSubTypes.cxx new file mode 100644 index 00000000000..9efeedb04cd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationTypePubSubTypes.cxx @@ -0,0 +1,194 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file StationTypePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "StationTypePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace StationType_Constants { + + + + + + + + + + + + + + + + + } //End of namespace StationType_Constants + StationTypePubSubType::StationTypePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::StationType_"); + auto type_size = StationType::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = StationType::isKeyDefined(); + size_t keyLength = StationType::getKeyMaxCdrSerializedSize() > 16 ? + StationType::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + StationTypePubSubType::~StationTypePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool StationTypePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + StationType* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool StationTypePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + StationType* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function StationTypePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* StationTypePubSubType::createData() + { + return reinterpret_cast(new StationType()); + } + + void StationTypePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool StationTypePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + StationType* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + StationType::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || StationType::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationTypePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationTypePubSubTypes.h new file mode 100644 index 00000000000..df1af41207c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationTypePubSubTypes.h @@ -0,0 +1,125 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file StationTypePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONTYPE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONTYPE_PUBSUBTYPES_H_ + +#include +#include + +#include "StationType.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated StationType is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace StationType_Constants + { + + + + + + + + + + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type StationType defined by the user in the IDL file. + * @ingroup STATIONTYPE + */ + class StationTypePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef StationType type; + + eProsima_user_DllExport StationTypePubSubType(); + + eProsima_user_DllExport virtual ~StationTypePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) StationType(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONTYPE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngle.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngle.cxx new file mode 100644 index 00000000000..59e0e867a0d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngle.cxx @@ -0,0 +1,238 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SteeringWheelAngle.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "SteeringWheelAngle.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::SteeringWheelAngle::SteeringWheelAngle() +{ + // m_steering_wheel_angle_value com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@89c65d5 + + // m_steering_wheel_angle_confidence com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@faa3fed + + +} + +etsi_its_cam_msgs::msg::SteeringWheelAngle::~SteeringWheelAngle() +{ + +} + +etsi_its_cam_msgs::msg::SteeringWheelAngle::SteeringWheelAngle( + const SteeringWheelAngle& x) +{ + m_steering_wheel_angle_value = x.m_steering_wheel_angle_value; + m_steering_wheel_angle_confidence = x.m_steering_wheel_angle_confidence; +} + +etsi_its_cam_msgs::msg::SteeringWheelAngle::SteeringWheelAngle( + SteeringWheelAngle&& x) +{ + m_steering_wheel_angle_value = std::move(x.m_steering_wheel_angle_value); + m_steering_wheel_angle_confidence = std::move(x.m_steering_wheel_angle_confidence); +} + +etsi_its_cam_msgs::msg::SteeringWheelAngle& etsi_its_cam_msgs::msg::SteeringWheelAngle::operator =( + const SteeringWheelAngle& x) +{ + + m_steering_wheel_angle_value = x.m_steering_wheel_angle_value; + m_steering_wheel_angle_confidence = x.m_steering_wheel_angle_confidence; + + return *this; +} + +etsi_its_cam_msgs::msg::SteeringWheelAngle& etsi_its_cam_msgs::msg::SteeringWheelAngle::operator =( + SteeringWheelAngle&& x) +{ + + m_steering_wheel_angle_value = std::move(x.m_steering_wheel_angle_value); + m_steering_wheel_angle_confidence = std::move(x.m_steering_wheel_angle_confidence); + + return *this; +} + +bool etsi_its_cam_msgs::msg::SteeringWheelAngle::operator ==( + const SteeringWheelAngle& x) const +{ + + return (m_steering_wheel_angle_value == x.m_steering_wheel_angle_value && m_steering_wheel_angle_confidence == x.m_steering_wheel_angle_confidence); +} + +bool etsi_its_cam_msgs::msg::SteeringWheelAngle::operator !=( + const SteeringWheelAngle& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::SteeringWheelAngle::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::SteeringWheelAngleValue::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::SteeringWheelAngle::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SteeringWheelAngle& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::SteeringWheelAngleValue::getCdrSerializedSize(data.steering_wheel_angle_value(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence::getCdrSerializedSize(data.steering_wheel_angle_confidence(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::SteeringWheelAngle::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_steering_wheel_angle_value; + scdr << m_steering_wheel_angle_confidence; + +} + +void etsi_its_cam_msgs::msg::SteeringWheelAngle::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_steering_wheel_angle_value; + dcdr >> m_steering_wheel_angle_confidence; +} + +/*! + * @brief This function copies the value in member steering_wheel_angle_value + * @param _steering_wheel_angle_value New value to be copied in member steering_wheel_angle_value + */ +void etsi_its_cam_msgs::msg::SteeringWheelAngle::steering_wheel_angle_value( + const etsi_its_cam_msgs::msg::SteeringWheelAngleValue& _steering_wheel_angle_value) +{ + m_steering_wheel_angle_value = _steering_wheel_angle_value; +} + +/*! + * @brief This function moves the value in member steering_wheel_angle_value + * @param _steering_wheel_angle_value New value to be moved in member steering_wheel_angle_value + */ +void etsi_its_cam_msgs::msg::SteeringWheelAngle::steering_wheel_angle_value( + etsi_its_cam_msgs::msg::SteeringWheelAngleValue&& _steering_wheel_angle_value) +{ + m_steering_wheel_angle_value = std::move(_steering_wheel_angle_value); +} + +/*! + * @brief This function returns a constant reference to member steering_wheel_angle_value + * @return Constant reference to member steering_wheel_angle_value + */ +const etsi_its_cam_msgs::msg::SteeringWheelAngleValue& etsi_its_cam_msgs::msg::SteeringWheelAngle::steering_wheel_angle_value() const +{ + return m_steering_wheel_angle_value; +} + +/*! + * @brief This function returns a reference to member steering_wheel_angle_value + * @return Reference to member steering_wheel_angle_value + */ +etsi_its_cam_msgs::msg::SteeringWheelAngleValue& etsi_its_cam_msgs::msg::SteeringWheelAngle::steering_wheel_angle_value() +{ + return m_steering_wheel_angle_value; +} +/*! + * @brief This function copies the value in member steering_wheel_angle_confidence + * @param _steering_wheel_angle_confidence New value to be copied in member steering_wheel_angle_confidence + */ +void etsi_its_cam_msgs::msg::SteeringWheelAngle::steering_wheel_angle_confidence( + const etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence& _steering_wheel_angle_confidence) +{ + m_steering_wheel_angle_confidence = _steering_wheel_angle_confidence; +} + +/*! + * @brief This function moves the value in member steering_wheel_angle_confidence + * @param _steering_wheel_angle_confidence New value to be moved in member steering_wheel_angle_confidence + */ +void etsi_its_cam_msgs::msg::SteeringWheelAngle::steering_wheel_angle_confidence( + etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence&& _steering_wheel_angle_confidence) +{ + m_steering_wheel_angle_confidence = std::move(_steering_wheel_angle_confidence); +} + +/*! + * @brief This function returns a constant reference to member steering_wheel_angle_confidence + * @return Constant reference to member steering_wheel_angle_confidence + */ +const etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence& etsi_its_cam_msgs::msg::SteeringWheelAngle::steering_wheel_angle_confidence() const +{ + return m_steering_wheel_angle_confidence; +} + +/*! + * @brief This function returns a reference to member steering_wheel_angle_confidence + * @return Reference to member steering_wheel_angle_confidence + */ +etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence& etsi_its_cam_msgs::msg::SteeringWheelAngle::steering_wheel_angle_confidence() +{ + return m_steering_wheel_angle_confidence; +} + +size_t etsi_its_cam_msgs::msg::SteeringWheelAngle::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::SteeringWheelAngle::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::SteeringWheelAngle::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngle.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngle.h new file mode 100644 index 00000000000..6287e887d4b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngle.h @@ -0,0 +1,244 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SteeringWheelAngle.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLE_H_ + +#include "SteeringWheelAngleConfidence.h" +#include "SteeringWheelAngleValue.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(SteeringWheelAngle_SOURCE) +#define SteeringWheelAngle_DllAPI __declspec( dllexport ) +#else +#define SteeringWheelAngle_DllAPI __declspec( dllimport ) +#endif // SteeringWheelAngle_SOURCE +#else +#define SteeringWheelAngle_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define SteeringWheelAngle_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure SteeringWheelAngle defined by the user in the IDL file. + * @ingroup STEERINGWHEELANGLE + */ + class SteeringWheelAngle + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport SteeringWheelAngle(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~SteeringWheelAngle(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SteeringWheelAngle that will be copied. + */ + eProsima_user_DllExport SteeringWheelAngle( + const SteeringWheelAngle& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SteeringWheelAngle that will be copied. + */ + eProsima_user_DllExport SteeringWheelAngle( + SteeringWheelAngle&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SteeringWheelAngle that will be copied. + */ + eProsima_user_DllExport SteeringWheelAngle& operator =( + const SteeringWheelAngle& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SteeringWheelAngle that will be copied. + */ + eProsima_user_DllExport SteeringWheelAngle& operator =( + SteeringWheelAngle&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SteeringWheelAngle object to compare. + */ + eProsima_user_DllExport bool operator ==( + const SteeringWheelAngle& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SteeringWheelAngle object to compare. + */ + eProsima_user_DllExport bool operator !=( + const SteeringWheelAngle& x) const; + + /*! + * @brief This function copies the value in member steering_wheel_angle_value + * @param _steering_wheel_angle_value New value to be copied in member steering_wheel_angle_value + */ + eProsima_user_DllExport void steering_wheel_angle_value( + const etsi_its_cam_msgs::msg::SteeringWheelAngleValue& _steering_wheel_angle_value); + + /*! + * @brief This function moves the value in member steering_wheel_angle_value + * @param _steering_wheel_angle_value New value to be moved in member steering_wheel_angle_value + */ + eProsima_user_DllExport void steering_wheel_angle_value( + etsi_its_cam_msgs::msg::SteeringWheelAngleValue&& _steering_wheel_angle_value); + + /*! + * @brief This function returns a constant reference to member steering_wheel_angle_value + * @return Constant reference to member steering_wheel_angle_value + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::SteeringWheelAngleValue& steering_wheel_angle_value() const; + + /*! + * @brief This function returns a reference to member steering_wheel_angle_value + * @return Reference to member steering_wheel_angle_value + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::SteeringWheelAngleValue& steering_wheel_angle_value(); + /*! + * @brief This function copies the value in member steering_wheel_angle_confidence + * @param _steering_wheel_angle_confidence New value to be copied in member steering_wheel_angle_confidence + */ + eProsima_user_DllExport void steering_wheel_angle_confidence( + const etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence& _steering_wheel_angle_confidence); + + /*! + * @brief This function moves the value in member steering_wheel_angle_confidence + * @param _steering_wheel_angle_confidence New value to be moved in member steering_wheel_angle_confidence + */ + eProsima_user_DllExport void steering_wheel_angle_confidence( + etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence&& _steering_wheel_angle_confidence); + + /*! + * @brief This function returns a constant reference to member steering_wheel_angle_confidence + * @return Constant reference to member steering_wheel_angle_confidence + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence& steering_wheel_angle_confidence() const; + + /*! + * @brief This function returns a reference to member steering_wheel_angle_confidence + * @return Reference to member steering_wheel_angle_confidence + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence& steering_wheel_angle_confidence(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SteeringWheelAngle& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::SteeringWheelAngleValue m_steering_wheel_angle_value; + etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence m_steering_wheel_angle_confidence; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.cxx new file mode 100644 index 00000000000..d9cee4202da --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.cxx @@ -0,0 +1,189 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SteeringWheelAngleConfidence.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "SteeringWheelAngleConfidence.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + +etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence::SteeringWheelAngleConfidence() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@400d912a + m_value = 0; + +} + +etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence::~SteeringWheelAngleConfidence() +{ +} + +etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence::SteeringWheelAngleConfidence( + const SteeringWheelAngleConfidence& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence::SteeringWheelAngleConfidence( + SteeringWheelAngleConfidence&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence& etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence::operator =( + const SteeringWheelAngleConfidence& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence& etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence::operator =( + SteeringWheelAngleConfidence&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence::operator ==( + const SteeringWheelAngleConfidence& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence::operator !=( + const SteeringWheelAngleConfidence& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.h new file mode 100644 index 00000000000..d582bf820f0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SteeringWheelAngleConfidence.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLECONFIDENCE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLECONFIDENCE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(SteeringWheelAngleConfidence_SOURCE) +#define SteeringWheelAngleConfidence_DllAPI __declspec( dllexport ) +#else +#define SteeringWheelAngleConfidence_DllAPI __declspec( dllimport ) +#endif // SteeringWheelAngleConfidence_SOURCE +#else +#define SteeringWheelAngleConfidence_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define SteeringWheelAngleConfidence_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace SteeringWheelAngleConfidence_Constants { + const uint8_t MIN = 1; + const uint8_t MAX = 127; + const uint8_t EQUAL_OR_WITHIN_ONE_POINT_FIVE_DEGREE = 1; + const uint8_t OUT_OF_RANGE = 126; + const uint8_t UNAVAILABLE = 127; + } // namespace SteeringWheelAngleConfidence_Constants + /*! + * @brief This class represents the structure SteeringWheelAngleConfidence defined by the user in the IDL file. + * @ingroup STEERINGWHEELANGLECONFIDENCE + */ + class SteeringWheelAngleConfidence + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport SteeringWheelAngleConfidence(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~SteeringWheelAngleConfidence(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence that will be copied. + */ + eProsima_user_DllExport SteeringWheelAngleConfidence( + const SteeringWheelAngleConfidence& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence that will be copied. + */ + eProsima_user_DllExport SteeringWheelAngleConfidence( + SteeringWheelAngleConfidence&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence that will be copied. + */ + eProsima_user_DllExport SteeringWheelAngleConfidence& operator =( + const SteeringWheelAngleConfidence& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence that will be copied. + */ + eProsima_user_DllExport SteeringWheelAngleConfidence& operator =( + SteeringWheelAngleConfidence&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence object to compare. + */ + eProsima_user_DllExport bool operator ==( + const SteeringWheelAngleConfidence& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence object to compare. + */ + eProsima_user_DllExport bool operator !=( + const SteeringWheelAngleConfidence& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLECONFIDENCE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidencePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidencePubSubTypes.cxx new file mode 100644 index 00000000000..2b5fe2baaad --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidencePubSubTypes.cxx @@ -0,0 +1,184 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SteeringWheelAngleConfidencePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "SteeringWheelAngleConfidencePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace SteeringWheelAngleConfidence_Constants { + + + + + + + } //End of namespace SteeringWheelAngleConfidence_Constants + SteeringWheelAngleConfidencePubSubType::SteeringWheelAngleConfidencePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::SteeringWheelAngleConfidence_"); + auto type_size = SteeringWheelAngleConfidence::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = SteeringWheelAngleConfidence::isKeyDefined(); + size_t keyLength = SteeringWheelAngleConfidence::getKeyMaxCdrSerializedSize() > 16 ? + SteeringWheelAngleConfidence::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + SteeringWheelAngleConfidencePubSubType::~SteeringWheelAngleConfidencePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool SteeringWheelAngleConfidencePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + SteeringWheelAngleConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool SteeringWheelAngleConfidencePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + SteeringWheelAngleConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function SteeringWheelAngleConfidencePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* SteeringWheelAngleConfidencePubSubType::createData() + { + return reinterpret_cast(new SteeringWheelAngleConfidence()); + } + + void SteeringWheelAngleConfidencePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool SteeringWheelAngleConfidencePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + SteeringWheelAngleConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + SteeringWheelAngleConfidence::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || SteeringWheelAngleConfidence::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidencePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidencePubSubTypes.h new file mode 100644 index 00000000000..f294f5cc3a0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidencePubSubTypes.h @@ -0,0 +1,115 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SteeringWheelAngleConfidencePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLECONFIDENCE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLECONFIDENCE_PUBSUBTYPES_H_ + +#include +#include + +#include "SteeringWheelAngleConfidence.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated SteeringWheelAngleConfidence is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace SteeringWheelAngleConfidence_Constants + { + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type SteeringWheelAngleConfidence defined by the user in the IDL file. + * @ingroup STEERINGWHEELANGLECONFIDENCE + */ + class SteeringWheelAngleConfidencePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef SteeringWheelAngleConfidence type; + + eProsima_user_DllExport SteeringWheelAngleConfidencePubSubType(); + + eProsima_user_DllExport virtual ~SteeringWheelAngleConfidencePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) SteeringWheelAngleConfidence(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLECONFIDENCE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAnglePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAnglePubSubTypes.cxx new file mode 100644 index 00000000000..543b4a07415 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAnglePubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SteeringWheelAnglePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "SteeringWheelAnglePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + SteeringWheelAnglePubSubType::SteeringWheelAnglePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::SteeringWheelAngle_"); + auto type_size = SteeringWheelAngle::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = SteeringWheelAngle::isKeyDefined(); + size_t keyLength = SteeringWheelAngle::getKeyMaxCdrSerializedSize() > 16 ? + SteeringWheelAngle::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + SteeringWheelAnglePubSubType::~SteeringWheelAnglePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool SteeringWheelAnglePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + SteeringWheelAngle* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool SteeringWheelAnglePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + SteeringWheelAngle* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function SteeringWheelAnglePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* SteeringWheelAnglePubSubType::createData() + { + return reinterpret_cast(new SteeringWheelAngle()); + } + + void SteeringWheelAnglePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool SteeringWheelAnglePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + SteeringWheelAngle* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + SteeringWheelAngle::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || SteeringWheelAngle::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAnglePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAnglePubSubTypes.h new file mode 100644 index 00000000000..e68a26c4288 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAnglePubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SteeringWheelAnglePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLE_PUBSUBTYPES_H_ + +#include +#include + +#include "SteeringWheelAngle.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated SteeringWheelAngle is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type SteeringWheelAngle defined by the user in the IDL file. + * @ingroup STEERINGWHEELANGLE + */ + class SteeringWheelAnglePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef SteeringWheelAngle type; + + eProsima_user_DllExport SteeringWheelAnglePubSubType(); + + eProsima_user_DllExport virtual ~SteeringWheelAnglePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) SteeringWheelAngle(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.cxx new file mode 100644 index 00000000000..d742c6602cc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.cxx @@ -0,0 +1,190 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SteeringWheelAngleValue.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "SteeringWheelAngleValue.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + +etsi_its_cam_msgs::msg::SteeringWheelAngleValue::SteeringWheelAngleValue() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@456be73c + m_value = 0; + +} + +etsi_its_cam_msgs::msg::SteeringWheelAngleValue::~SteeringWheelAngleValue() +{ +} + +etsi_its_cam_msgs::msg::SteeringWheelAngleValue::SteeringWheelAngleValue( + const SteeringWheelAngleValue& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::SteeringWheelAngleValue::SteeringWheelAngleValue( + SteeringWheelAngleValue&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::SteeringWheelAngleValue& etsi_its_cam_msgs::msg::SteeringWheelAngleValue::operator =( + const SteeringWheelAngleValue& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::SteeringWheelAngleValue& etsi_its_cam_msgs::msg::SteeringWheelAngleValue::operator =( + SteeringWheelAngleValue&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::SteeringWheelAngleValue::operator ==( + const SteeringWheelAngleValue& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::SteeringWheelAngleValue::operator !=( + const SteeringWheelAngleValue& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::SteeringWheelAngleValue::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::SteeringWheelAngleValue::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SteeringWheelAngleValue& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::SteeringWheelAngleValue::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::SteeringWheelAngleValue::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::SteeringWheelAngleValue::value( + int16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int16_t etsi_its_cam_msgs::msg::SteeringWheelAngleValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int16_t& etsi_its_cam_msgs::msg::SteeringWheelAngleValue::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::SteeringWheelAngleValue::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::SteeringWheelAngleValue::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::SteeringWheelAngleValue::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.h new file mode 100644 index 00000000000..a7702bff64d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.h @@ -0,0 +1,218 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SteeringWheelAngleValue.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLEVALUE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLEVALUE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(SteeringWheelAngleValue_SOURCE) +#define SteeringWheelAngleValue_DllAPI __declspec( dllexport ) +#else +#define SteeringWheelAngleValue_DllAPI __declspec( dllimport ) +#endif // SteeringWheelAngleValue_SOURCE +#else +#define SteeringWheelAngleValue_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define SteeringWheelAngleValue_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace SteeringWheelAngleValue_Constants { + const int16_t MIN = -511; + const int16_t MAX = 512; + const int16_t STRAIGHT = 0; + const int16_t ONE_POINT_FIVE_DEGREES_TO_RIGHT = -1; + const int16_t ONE_POINT_FIVE_DEGREES_TO_LEFT = 1; + const int16_t UNAVAILABLE = 512; + } // namespace SteeringWheelAngleValue_Constants + /*! + * @brief This class represents the structure SteeringWheelAngleValue defined by the user in the IDL file. + * @ingroup STEERINGWHEELANGLEVALUE + */ + class SteeringWheelAngleValue + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport SteeringWheelAngleValue(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~SteeringWheelAngleValue(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SteeringWheelAngleValue that will be copied. + */ + eProsima_user_DllExport SteeringWheelAngleValue( + const SteeringWheelAngleValue& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SteeringWheelAngleValue that will be copied. + */ + eProsima_user_DllExport SteeringWheelAngleValue( + SteeringWheelAngleValue&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SteeringWheelAngleValue that will be copied. + */ + eProsima_user_DllExport SteeringWheelAngleValue& operator =( + const SteeringWheelAngleValue& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SteeringWheelAngleValue that will be copied. + */ + eProsima_user_DllExport SteeringWheelAngleValue& operator =( + SteeringWheelAngleValue&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SteeringWheelAngleValue object to compare. + */ + eProsima_user_DllExport bool operator ==( + const SteeringWheelAngleValue& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SteeringWheelAngleValue object to compare. + */ + eProsima_user_DllExport bool operator !=( + const SteeringWheelAngleValue& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + int16_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport int16_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport int16_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SteeringWheelAngleValue& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + int16_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLEVALUE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValuePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValuePubSubTypes.cxx new file mode 100644 index 00000000000..ad25606f66a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValuePubSubTypes.cxx @@ -0,0 +1,185 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SteeringWheelAngleValuePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "SteeringWheelAngleValuePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace SteeringWheelAngleValue_Constants { + + + + + + + + } //End of namespace SteeringWheelAngleValue_Constants + SteeringWheelAngleValuePubSubType::SteeringWheelAngleValuePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::SteeringWheelAngleValue_"); + auto type_size = SteeringWheelAngleValue::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = SteeringWheelAngleValue::isKeyDefined(); + size_t keyLength = SteeringWheelAngleValue::getKeyMaxCdrSerializedSize() > 16 ? + SteeringWheelAngleValue::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + SteeringWheelAngleValuePubSubType::~SteeringWheelAngleValuePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool SteeringWheelAngleValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + SteeringWheelAngleValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool SteeringWheelAngleValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + SteeringWheelAngleValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function SteeringWheelAngleValuePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* SteeringWheelAngleValuePubSubType::createData() + { + return reinterpret_cast(new SteeringWheelAngleValue()); + } + + void SteeringWheelAngleValuePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool SteeringWheelAngleValuePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + SteeringWheelAngleValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + SteeringWheelAngleValue::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || SteeringWheelAngleValue::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValuePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValuePubSubTypes.h new file mode 100644 index 00000000000..96b5b2f7d8e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValuePubSubTypes.h @@ -0,0 +1,116 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SteeringWheelAngleValuePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLEVALUE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLEVALUE_PUBSUBTYPES_H_ + +#include +#include + +#include "SteeringWheelAngleValue.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated SteeringWheelAngleValue is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace SteeringWheelAngleValue_Constants + { + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type SteeringWheelAngleValue defined by the user in the IDL file. + * @ingroup STEERINGWHEELANGLEVALUE + */ + class SteeringWheelAngleValuePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef SteeringWheelAngleValue type; + + eProsima_user_DllExport SteeringWheelAngleValuePubSubType(); + + eProsima_user_DllExport virtual ~SteeringWheelAngleValuePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) SteeringWheelAngleValue(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLEVALUE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeType.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeType.cxx new file mode 100644 index 00000000000..d709f6c4764 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeType.cxx @@ -0,0 +1,186 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SubCauseCodeType.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "SubCauseCodeType.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + +etsi_its_cam_msgs::msg::SubCauseCodeType::SubCauseCodeType() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@8ab78bc + m_value = 0; + +} + +etsi_its_cam_msgs::msg::SubCauseCodeType::~SubCauseCodeType() +{ +} + +etsi_its_cam_msgs::msg::SubCauseCodeType::SubCauseCodeType( + const SubCauseCodeType& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::SubCauseCodeType::SubCauseCodeType( + SubCauseCodeType&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::SubCauseCodeType& etsi_its_cam_msgs::msg::SubCauseCodeType::operator =( + const SubCauseCodeType& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::SubCauseCodeType& etsi_its_cam_msgs::msg::SubCauseCodeType::operator =( + SubCauseCodeType&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::SubCauseCodeType::operator ==( + const SubCauseCodeType& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::SubCauseCodeType::operator !=( + const SubCauseCodeType& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::SubCauseCodeType::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::SubCauseCodeType::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SubCauseCodeType& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::SubCauseCodeType::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::SubCauseCodeType::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::SubCauseCodeType::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::SubCauseCodeType::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::SubCauseCodeType::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::SubCauseCodeType::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::SubCauseCodeType::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::SubCauseCodeType::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeType.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeType.h new file mode 100644 index 00000000000..a9660bba5a7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeType.h @@ -0,0 +1,214 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SubCauseCodeType.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SUBCAUSECODETYPE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SUBCAUSECODETYPE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(SubCauseCodeType_SOURCE) +#define SubCauseCodeType_DllAPI __declspec( dllexport ) +#else +#define SubCauseCodeType_DllAPI __declspec( dllimport ) +#endif // SubCauseCodeType_SOURCE +#else +#define SubCauseCodeType_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define SubCauseCodeType_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace SubCauseCodeType_Constants { + const uint8_t MIN = 0; + const uint8_t MAX = 255; + } // namespace SubCauseCodeType_Constants + /*! + * @brief This class represents the structure SubCauseCodeType defined by the user in the IDL file. + * @ingroup SUBCAUSECODETYPE + */ + class SubCauseCodeType + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport SubCauseCodeType(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~SubCauseCodeType(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SubCauseCodeType that will be copied. + */ + eProsima_user_DllExport SubCauseCodeType( + const SubCauseCodeType& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::SubCauseCodeType that will be copied. + */ + eProsima_user_DllExport SubCauseCodeType( + SubCauseCodeType&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SubCauseCodeType that will be copied. + */ + eProsima_user_DllExport SubCauseCodeType& operator =( + const SubCauseCodeType& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::SubCauseCodeType that will be copied. + */ + eProsima_user_DllExport SubCauseCodeType& operator =( + SubCauseCodeType&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SubCauseCodeType object to compare. + */ + eProsima_user_DllExport bool operator ==( + const SubCauseCodeType& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::SubCauseCodeType object to compare. + */ + eProsima_user_DllExport bool operator !=( + const SubCauseCodeType& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::SubCauseCodeType& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SUBCAUSECODETYPE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeTypePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeTypePubSubTypes.cxx new file mode 100644 index 00000000000..13465ad99bc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeTypePubSubTypes.cxx @@ -0,0 +1,181 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SubCauseCodeTypePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "SubCauseCodeTypePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace SubCauseCodeType_Constants { + + + + } //End of namespace SubCauseCodeType_Constants + SubCauseCodeTypePubSubType::SubCauseCodeTypePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::SubCauseCodeType_"); + auto type_size = SubCauseCodeType::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = SubCauseCodeType::isKeyDefined(); + size_t keyLength = SubCauseCodeType::getKeyMaxCdrSerializedSize() > 16 ? + SubCauseCodeType::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + SubCauseCodeTypePubSubType::~SubCauseCodeTypePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool SubCauseCodeTypePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + SubCauseCodeType* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool SubCauseCodeTypePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + SubCauseCodeType* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function SubCauseCodeTypePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* SubCauseCodeTypePubSubType::createData() + { + return reinterpret_cast(new SubCauseCodeType()); + } + + void SubCauseCodeTypePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool SubCauseCodeTypePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + SubCauseCodeType* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + SubCauseCodeType::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || SubCauseCodeType::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeTypePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeTypePubSubTypes.h new file mode 100644 index 00000000000..8e93c1cde2e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeTypePubSubTypes.h @@ -0,0 +1,112 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SubCauseCodeTypePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SUBCAUSECODETYPE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SUBCAUSECODETYPE_PUBSUBTYPES_H_ + +#include +#include + +#include "SubCauseCodeType.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated SubCauseCodeType is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace SubCauseCodeType_Constants + { + + + } + /*! + * @brief This class represents the TopicDataType of the type SubCauseCodeType defined by the user in the IDL file. + * @ingroup SUBCAUSECODETYPE + */ + class SubCauseCodeTypePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef SubCauseCodeType type; + + eProsima_user_DllExport SubCauseCodeTypePubSubType(); + + eProsima_user_DllExport virtual ~SubCauseCodeTypePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) SubCauseCodeType(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SUBCAUSECODETYPE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampIts.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampIts.cxx new file mode 100644 index 00000000000..0e3a486c4ab --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampIts.cxx @@ -0,0 +1,188 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file TimestampIts.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "TimestampIts.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + +etsi_its_cam_msgs::msg::TimestampIts::TimestampIts() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@4163f1cd + m_value = 0; + +} + +etsi_its_cam_msgs::msg::TimestampIts::~TimestampIts() +{ +} + +etsi_its_cam_msgs::msg::TimestampIts::TimestampIts( + const TimestampIts& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::TimestampIts::TimestampIts( + TimestampIts&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::TimestampIts& etsi_its_cam_msgs::msg::TimestampIts::operator =( + const TimestampIts& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::TimestampIts& etsi_its_cam_msgs::msg::TimestampIts::operator =( + TimestampIts&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::TimestampIts::operator ==( + const TimestampIts& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::TimestampIts::operator !=( + const TimestampIts& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::TimestampIts::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::TimestampIts::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::TimestampIts& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::TimestampIts::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::TimestampIts::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::TimestampIts::value( + uint64_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint64_t etsi_its_cam_msgs::msg::TimestampIts::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint64_t& etsi_its_cam_msgs::msg::TimestampIts::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::TimestampIts::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::TimestampIts::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::TimestampIts::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampIts.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampIts.h new file mode 100644 index 00000000000..03a4a76a376 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampIts.h @@ -0,0 +1,216 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file TimestampIts.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TIMESTAMPITS_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TIMESTAMPITS_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(TimestampIts_SOURCE) +#define TimestampIts_DllAPI __declspec( dllexport ) +#else +#define TimestampIts_DllAPI __declspec( dllimport ) +#endif // TimestampIts_SOURCE +#else +#define TimestampIts_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define TimestampIts_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace TimestampIts_Constants { + const uint64_t MIN = 0; + const uint64_t MAX = 4398046511103; + const uint64_t UTC_START_OF_2004 = 0; + const uint64_t ONE_MILLISEC_AFTER_UTC_START_OF_2004 = 1; + } // namespace TimestampIts_Constants + /*! + * @brief This class represents the structure TimestampIts defined by the user in the IDL file. + * @ingroup TIMESTAMPITS + */ + class TimestampIts + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport TimestampIts(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~TimestampIts(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::TimestampIts that will be copied. + */ + eProsima_user_DllExport TimestampIts( + const TimestampIts& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::TimestampIts that will be copied. + */ + eProsima_user_DllExport TimestampIts( + TimestampIts&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::TimestampIts that will be copied. + */ + eProsima_user_DllExport TimestampIts& operator =( + const TimestampIts& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::TimestampIts that will be copied. + */ + eProsima_user_DllExport TimestampIts& operator =( + TimestampIts&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::TimestampIts object to compare. + */ + eProsima_user_DllExport bool operator ==( + const TimestampIts& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::TimestampIts object to compare. + */ + eProsima_user_DllExport bool operator !=( + const TimestampIts& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint64_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint64_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint64_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::TimestampIts& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint64_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TIMESTAMPITS_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampItsPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampItsPubSubTypes.cxx new file mode 100644 index 00000000000..30a817f4b8c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampItsPubSubTypes.cxx @@ -0,0 +1,183 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file TimestampItsPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "TimestampItsPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace TimestampIts_Constants { + + + + + + } //End of namespace TimestampIts_Constants + TimestampItsPubSubType::TimestampItsPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::TimestampIts_"); + auto type_size = TimestampIts::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = TimestampIts::isKeyDefined(); + size_t keyLength = TimestampIts::getKeyMaxCdrSerializedSize() > 16 ? + TimestampIts::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + TimestampItsPubSubType::~TimestampItsPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool TimestampItsPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + TimestampIts* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool TimestampItsPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + TimestampIts* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function TimestampItsPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* TimestampItsPubSubType::createData() + { + return reinterpret_cast(new TimestampIts()); + } + + void TimestampItsPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool TimestampItsPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + TimestampIts* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + TimestampIts::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || TimestampIts::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampItsPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampItsPubSubTypes.h new file mode 100644 index 00000000000..56f04f21f6e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampItsPubSubTypes.h @@ -0,0 +1,114 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file TimestampItsPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TIMESTAMPITS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TIMESTAMPITS_PUBSUBTYPES_H_ + +#include +#include + +#include "TimestampIts.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated TimestampIts is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace TimestampIts_Constants + { + + + + + } + /*! + * @brief This class represents the TopicDataType of the type TimestampIts defined by the user in the IDL file. + * @ingroup TIMESTAMPITS + */ + class TimestampItsPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef TimestampIts type; + + eProsima_user_DllExport TimestampItsPubSubType(); + + eProsima_user_DllExport virtual ~TimestampItsPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) TimestampIts(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TIMESTAMPITS_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRule.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRule.cxx new file mode 100644 index 00000000000..3e5fcc040a9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRule.cxx @@ -0,0 +1,188 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file TrafficRule.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "TrafficRule.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + +etsi_its_cam_msgs::msg::TrafficRule::TrafficRule() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@44c79f32 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::TrafficRule::~TrafficRule() +{ +} + +etsi_its_cam_msgs::msg::TrafficRule::TrafficRule( + const TrafficRule& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::TrafficRule::TrafficRule( + TrafficRule&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::TrafficRule& etsi_its_cam_msgs::msg::TrafficRule::operator =( + const TrafficRule& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::TrafficRule& etsi_its_cam_msgs::msg::TrafficRule::operator =( + TrafficRule&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::TrafficRule::operator ==( + const TrafficRule& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::TrafficRule::operator !=( + const TrafficRule& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::TrafficRule::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::TrafficRule::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::TrafficRule& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::TrafficRule::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::TrafficRule::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::TrafficRule::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::TrafficRule::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::TrafficRule::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::TrafficRule::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::TrafficRule::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::TrafficRule::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRule.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRule.h new file mode 100644 index 00000000000..1c74abe5183 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRule.h @@ -0,0 +1,216 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file TrafficRule.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TRAFFICRULE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TRAFFICRULE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(TrafficRule_SOURCE) +#define TrafficRule_DllAPI __declspec( dllexport ) +#else +#define TrafficRule_DllAPI __declspec( dllimport ) +#endif // TrafficRule_SOURCE +#else +#define TrafficRule_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define TrafficRule_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace TrafficRule_Constants { + const uint8_t NO_PASSING = 0; + const uint8_t NO_PASSING_FOR_TRUCKS = 1; + const uint8_t PASS_TO_RIGHT = 2; + const uint8_t PASS_TO_LEFT = 3; + } // namespace TrafficRule_Constants + /*! + * @brief This class represents the structure TrafficRule defined by the user in the IDL file. + * @ingroup TRAFFICRULE + */ + class TrafficRule + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport TrafficRule(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~TrafficRule(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::TrafficRule that will be copied. + */ + eProsima_user_DllExport TrafficRule( + const TrafficRule& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::TrafficRule that will be copied. + */ + eProsima_user_DllExport TrafficRule( + TrafficRule&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::TrafficRule that will be copied. + */ + eProsima_user_DllExport TrafficRule& operator =( + const TrafficRule& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::TrafficRule that will be copied. + */ + eProsima_user_DllExport TrafficRule& operator =( + TrafficRule&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::TrafficRule object to compare. + */ + eProsima_user_DllExport bool operator ==( + const TrafficRule& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::TrafficRule object to compare. + */ + eProsima_user_DllExport bool operator !=( + const TrafficRule& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::TrafficRule& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TRAFFICRULE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRulePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRulePubSubTypes.cxx new file mode 100644 index 00000000000..279cfd5846c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRulePubSubTypes.cxx @@ -0,0 +1,183 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file TrafficRulePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "TrafficRulePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace TrafficRule_Constants { + + + + + + } //End of namespace TrafficRule_Constants + TrafficRulePubSubType::TrafficRulePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::TrafficRule_"); + auto type_size = TrafficRule::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = TrafficRule::isKeyDefined(); + size_t keyLength = TrafficRule::getKeyMaxCdrSerializedSize() > 16 ? + TrafficRule::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + TrafficRulePubSubType::~TrafficRulePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool TrafficRulePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + TrafficRule* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool TrafficRulePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + TrafficRule* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function TrafficRulePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* TrafficRulePubSubType::createData() + { + return reinterpret_cast(new TrafficRule()); + } + + void TrafficRulePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool TrafficRulePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + TrafficRule* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + TrafficRule::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || TrafficRule::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRulePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRulePubSubTypes.h new file mode 100644 index 00000000000..a5dc3e8de11 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRulePubSubTypes.h @@ -0,0 +1,114 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file TrafficRulePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TRAFFICRULE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TRAFFICRULE_PUBSUBTYPES_H_ + +#include +#include + +#include "TrafficRule.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated TrafficRule is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace TrafficRule_Constants + { + + + + + } + /*! + * @brief This class represents the TopicDataType of the type TrafficRule defined by the user in the IDL file. + * @ingroup TRAFFICRULE + */ + class TrafficRulePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef TrafficRule type; + + eProsima_user_DllExport TrafficRulePubSubType(); + + eProsima_user_DllExport virtual ~TrafficRulePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) TrafficRule(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TRAFFICRULE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLength.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLength.cxx new file mode 100644 index 00000000000..c6c9e1236cf --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLength.cxx @@ -0,0 +1,238 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VehicleLength.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "VehicleLength.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::VehicleLength::VehicleLength() +{ + // m_vehicle_length_value com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@48b0e701 + + // m_vehicle_length_confidence_indication com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@241a0c3a + + +} + +etsi_its_cam_msgs::msg::VehicleLength::~VehicleLength() +{ + +} + +etsi_its_cam_msgs::msg::VehicleLength::VehicleLength( + const VehicleLength& x) +{ + m_vehicle_length_value = x.m_vehicle_length_value; + m_vehicle_length_confidence_indication = x.m_vehicle_length_confidence_indication; +} + +etsi_its_cam_msgs::msg::VehicleLength::VehicleLength( + VehicleLength&& x) +{ + m_vehicle_length_value = std::move(x.m_vehicle_length_value); + m_vehicle_length_confidence_indication = std::move(x.m_vehicle_length_confidence_indication); +} + +etsi_its_cam_msgs::msg::VehicleLength& etsi_its_cam_msgs::msg::VehicleLength::operator =( + const VehicleLength& x) +{ + + m_vehicle_length_value = x.m_vehicle_length_value; + m_vehicle_length_confidence_indication = x.m_vehicle_length_confidence_indication; + + return *this; +} + +etsi_its_cam_msgs::msg::VehicleLength& etsi_its_cam_msgs::msg::VehicleLength::operator =( + VehicleLength&& x) +{ + + m_vehicle_length_value = std::move(x.m_vehicle_length_value); + m_vehicle_length_confidence_indication = std::move(x.m_vehicle_length_confidence_indication); + + return *this; +} + +bool etsi_its_cam_msgs::msg::VehicleLength::operator ==( + const VehicleLength& x) const +{ + + return (m_vehicle_length_value == x.m_vehicle_length_value && m_vehicle_length_confidence_indication == x.m_vehicle_length_confidence_indication); +} + +bool etsi_its_cam_msgs::msg::VehicleLength::operator !=( + const VehicleLength& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::VehicleLength::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::VehicleLengthValue::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::VehicleLength::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::VehicleLength& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::VehicleLengthValue::getCdrSerializedSize(data.vehicle_length_value(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication::getCdrSerializedSize(data.vehicle_length_confidence_indication(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::VehicleLength::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_vehicle_length_value; + scdr << m_vehicle_length_confidence_indication; + +} + +void etsi_its_cam_msgs::msg::VehicleLength::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_vehicle_length_value; + dcdr >> m_vehicle_length_confidence_indication; +} + +/*! + * @brief This function copies the value in member vehicle_length_value + * @param _vehicle_length_value New value to be copied in member vehicle_length_value + */ +void etsi_its_cam_msgs::msg::VehicleLength::vehicle_length_value( + const etsi_its_cam_msgs::msg::VehicleLengthValue& _vehicle_length_value) +{ + m_vehicle_length_value = _vehicle_length_value; +} + +/*! + * @brief This function moves the value in member vehicle_length_value + * @param _vehicle_length_value New value to be moved in member vehicle_length_value + */ +void etsi_its_cam_msgs::msg::VehicleLength::vehicle_length_value( + etsi_its_cam_msgs::msg::VehicleLengthValue&& _vehicle_length_value) +{ + m_vehicle_length_value = std::move(_vehicle_length_value); +} + +/*! + * @brief This function returns a constant reference to member vehicle_length_value + * @return Constant reference to member vehicle_length_value + */ +const etsi_its_cam_msgs::msg::VehicleLengthValue& etsi_its_cam_msgs::msg::VehicleLength::vehicle_length_value() const +{ + return m_vehicle_length_value; +} + +/*! + * @brief This function returns a reference to member vehicle_length_value + * @return Reference to member vehicle_length_value + */ +etsi_its_cam_msgs::msg::VehicleLengthValue& etsi_its_cam_msgs::msg::VehicleLength::vehicle_length_value() +{ + return m_vehicle_length_value; +} +/*! + * @brief This function copies the value in member vehicle_length_confidence_indication + * @param _vehicle_length_confidence_indication New value to be copied in member vehicle_length_confidence_indication + */ +void etsi_its_cam_msgs::msg::VehicleLength::vehicle_length_confidence_indication( + const etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication& _vehicle_length_confidence_indication) +{ + m_vehicle_length_confidence_indication = _vehicle_length_confidence_indication; +} + +/*! + * @brief This function moves the value in member vehicle_length_confidence_indication + * @param _vehicle_length_confidence_indication New value to be moved in member vehicle_length_confidence_indication + */ +void etsi_its_cam_msgs::msg::VehicleLength::vehicle_length_confidence_indication( + etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication&& _vehicle_length_confidence_indication) +{ + m_vehicle_length_confidence_indication = std::move(_vehicle_length_confidence_indication); +} + +/*! + * @brief This function returns a constant reference to member vehicle_length_confidence_indication + * @return Constant reference to member vehicle_length_confidence_indication + */ +const etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication& etsi_its_cam_msgs::msg::VehicleLength::vehicle_length_confidence_indication() const +{ + return m_vehicle_length_confidence_indication; +} + +/*! + * @brief This function returns a reference to member vehicle_length_confidence_indication + * @return Reference to member vehicle_length_confidence_indication + */ +etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication& etsi_its_cam_msgs::msg::VehicleLength::vehicle_length_confidence_indication() +{ + return m_vehicle_length_confidence_indication; +} + +size_t etsi_its_cam_msgs::msg::VehicleLength::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::VehicleLength::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::VehicleLength::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLength.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLength.h new file mode 100644 index 00000000000..87e83045daa --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLength.h @@ -0,0 +1,244 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VehicleLength.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTH_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTH_H_ + +#include "VehicleLengthValue.h" +#include "VehicleLengthConfidenceIndication.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(VehicleLength_SOURCE) +#define VehicleLength_DllAPI __declspec( dllexport ) +#else +#define VehicleLength_DllAPI __declspec( dllimport ) +#endif // VehicleLength_SOURCE +#else +#define VehicleLength_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define VehicleLength_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure VehicleLength defined by the user in the IDL file. + * @ingroup VEHICLELENGTH + */ + class VehicleLength + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport VehicleLength(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~VehicleLength(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::VehicleLength that will be copied. + */ + eProsima_user_DllExport VehicleLength( + const VehicleLength& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::VehicleLength that will be copied. + */ + eProsima_user_DllExport VehicleLength( + VehicleLength&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::VehicleLength that will be copied. + */ + eProsima_user_DllExport VehicleLength& operator =( + const VehicleLength& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::VehicleLength that will be copied. + */ + eProsima_user_DllExport VehicleLength& operator =( + VehicleLength&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::VehicleLength object to compare. + */ + eProsima_user_DllExport bool operator ==( + const VehicleLength& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::VehicleLength object to compare. + */ + eProsima_user_DllExport bool operator !=( + const VehicleLength& x) const; + + /*! + * @brief This function copies the value in member vehicle_length_value + * @param _vehicle_length_value New value to be copied in member vehicle_length_value + */ + eProsima_user_DllExport void vehicle_length_value( + const etsi_its_cam_msgs::msg::VehicleLengthValue& _vehicle_length_value); + + /*! + * @brief This function moves the value in member vehicle_length_value + * @param _vehicle_length_value New value to be moved in member vehicle_length_value + */ + eProsima_user_DllExport void vehicle_length_value( + etsi_its_cam_msgs::msg::VehicleLengthValue&& _vehicle_length_value); + + /*! + * @brief This function returns a constant reference to member vehicle_length_value + * @return Constant reference to member vehicle_length_value + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::VehicleLengthValue& vehicle_length_value() const; + + /*! + * @brief This function returns a reference to member vehicle_length_value + * @return Reference to member vehicle_length_value + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::VehicleLengthValue& vehicle_length_value(); + /*! + * @brief This function copies the value in member vehicle_length_confidence_indication + * @param _vehicle_length_confidence_indication New value to be copied in member vehicle_length_confidence_indication + */ + eProsima_user_DllExport void vehicle_length_confidence_indication( + const etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication& _vehicle_length_confidence_indication); + + /*! + * @brief This function moves the value in member vehicle_length_confidence_indication + * @param _vehicle_length_confidence_indication New value to be moved in member vehicle_length_confidence_indication + */ + eProsima_user_DllExport void vehicle_length_confidence_indication( + etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication&& _vehicle_length_confidence_indication); + + /*! + * @brief This function returns a constant reference to member vehicle_length_confidence_indication + * @return Constant reference to member vehicle_length_confidence_indication + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication& vehicle_length_confidence_indication() const; + + /*! + * @brief This function returns a reference to member vehicle_length_confidence_indication + * @return Reference to member vehicle_length_confidence_indication + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication& vehicle_length_confidence_indication(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::VehicleLength& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::VehicleLengthValue m_vehicle_length_value; + etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication m_vehicle_length_confidence_indication; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTH_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.cxx new file mode 100644 index 00000000000..3cab8baacdd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.cxx @@ -0,0 +1,189 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VehicleLengthConfidenceIndication.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "VehicleLengthConfidenceIndication.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + +etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication::VehicleLengthConfidenceIndication() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@4d7e7435 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication::~VehicleLengthConfidenceIndication() +{ +} + +etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication::VehicleLengthConfidenceIndication( + const VehicleLengthConfidenceIndication& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication::VehicleLengthConfidenceIndication( + VehicleLengthConfidenceIndication&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication& etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication::operator =( + const VehicleLengthConfidenceIndication& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication& etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication::operator =( + VehicleLengthConfidenceIndication&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication::operator ==( + const VehicleLengthConfidenceIndication& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication::operator !=( + const VehicleLengthConfidenceIndication& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.h new file mode 100644 index 00000000000..42f3fb4cd8a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VehicleLengthConfidenceIndication.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHCONFIDENCEINDICATION_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHCONFIDENCEINDICATION_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(VehicleLengthConfidenceIndication_SOURCE) +#define VehicleLengthConfidenceIndication_DllAPI __declspec( dllexport ) +#else +#define VehicleLengthConfidenceIndication_DllAPI __declspec( dllimport ) +#endif // VehicleLengthConfidenceIndication_SOURCE +#else +#define VehicleLengthConfidenceIndication_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define VehicleLengthConfidenceIndication_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace VehicleLengthConfidenceIndication_Constants { + const uint8_t NO_TRAILER_PRESENT = 0; + const uint8_t TRAILER_PRESENT_WITH_KNOWN_LENGTH = 1; + const uint8_t TRAILER_PRESENT_WITH_UNKNOWN_LENGTH = 2; + const uint8_t TRAILER_PRESENCE_IS_UNKNOWN = 3; + const uint8_t UNAVAILABLE = 4; + } // namespace VehicleLengthConfidenceIndication_Constants + /*! + * @brief This class represents the structure VehicleLengthConfidenceIndication defined by the user in the IDL file. + * @ingroup VEHICLELENGTHCONFIDENCEINDICATION + */ + class VehicleLengthConfidenceIndication + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport VehicleLengthConfidenceIndication(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~VehicleLengthConfidenceIndication(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication that will be copied. + */ + eProsima_user_DllExport VehicleLengthConfidenceIndication( + const VehicleLengthConfidenceIndication& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication that will be copied. + */ + eProsima_user_DllExport VehicleLengthConfidenceIndication( + VehicleLengthConfidenceIndication&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication that will be copied. + */ + eProsima_user_DllExport VehicleLengthConfidenceIndication& operator =( + const VehicleLengthConfidenceIndication& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication that will be copied. + */ + eProsima_user_DllExport VehicleLengthConfidenceIndication& operator =( + VehicleLengthConfidenceIndication&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication object to compare. + */ + eProsima_user_DllExport bool operator ==( + const VehicleLengthConfidenceIndication& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication object to compare. + */ + eProsima_user_DllExport bool operator !=( + const VehicleLengthConfidenceIndication& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHCONFIDENCEINDICATION_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndicationPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndicationPubSubTypes.cxx new file mode 100644 index 00000000000..6ece85a29e1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndicationPubSubTypes.cxx @@ -0,0 +1,184 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VehicleLengthConfidenceIndicationPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "VehicleLengthConfidenceIndicationPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace VehicleLengthConfidenceIndication_Constants { + + + + + + + } //End of namespace VehicleLengthConfidenceIndication_Constants + VehicleLengthConfidenceIndicationPubSubType::VehicleLengthConfidenceIndicationPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::VehicleLengthConfidenceIndication_"); + auto type_size = VehicleLengthConfidenceIndication::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = VehicleLengthConfidenceIndication::isKeyDefined(); + size_t keyLength = VehicleLengthConfidenceIndication::getKeyMaxCdrSerializedSize() > 16 ? + VehicleLengthConfidenceIndication::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + VehicleLengthConfidenceIndicationPubSubType::~VehicleLengthConfidenceIndicationPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool VehicleLengthConfidenceIndicationPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + VehicleLengthConfidenceIndication* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool VehicleLengthConfidenceIndicationPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + VehicleLengthConfidenceIndication* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function VehicleLengthConfidenceIndicationPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* VehicleLengthConfidenceIndicationPubSubType::createData() + { + return reinterpret_cast(new VehicleLengthConfidenceIndication()); + } + + void VehicleLengthConfidenceIndicationPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool VehicleLengthConfidenceIndicationPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + VehicleLengthConfidenceIndication* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + VehicleLengthConfidenceIndication::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || VehicleLengthConfidenceIndication::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndicationPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndicationPubSubTypes.h new file mode 100644 index 00000000000..e256a7a8097 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndicationPubSubTypes.h @@ -0,0 +1,115 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VehicleLengthConfidenceIndicationPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHCONFIDENCEINDICATION_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHCONFIDENCEINDICATION_PUBSUBTYPES_H_ + +#include +#include + +#include "VehicleLengthConfidenceIndication.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated VehicleLengthConfidenceIndication is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace VehicleLengthConfidenceIndication_Constants + { + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type VehicleLengthConfidenceIndication defined by the user in the IDL file. + * @ingroup VEHICLELENGTHCONFIDENCEINDICATION + */ + class VehicleLengthConfidenceIndicationPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef VehicleLengthConfidenceIndication type; + + eProsima_user_DllExport VehicleLengthConfidenceIndicationPubSubType(); + + eProsima_user_DllExport virtual ~VehicleLengthConfidenceIndicationPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) VehicleLengthConfidenceIndication(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHCONFIDENCEINDICATION_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthPubSubTypes.cxx new file mode 100644 index 00000000000..cf09e754801 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VehicleLengthPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "VehicleLengthPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + VehicleLengthPubSubType::VehicleLengthPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::VehicleLength_"); + auto type_size = VehicleLength::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = VehicleLength::isKeyDefined(); + size_t keyLength = VehicleLength::getKeyMaxCdrSerializedSize() > 16 ? + VehicleLength::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + VehicleLengthPubSubType::~VehicleLengthPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool VehicleLengthPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + VehicleLength* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool VehicleLengthPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + VehicleLength* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function VehicleLengthPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* VehicleLengthPubSubType::createData() + { + return reinterpret_cast(new VehicleLength()); + } + + void VehicleLengthPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool VehicleLengthPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + VehicleLength* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + VehicleLength::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || VehicleLength::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthPubSubTypes.h new file mode 100644 index 00000000000..b80d91d3f61 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VehicleLengthPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTH_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTH_PUBSUBTYPES_H_ + +#include +#include + +#include "VehicleLength.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated VehicleLength is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type VehicleLength defined by the user in the IDL file. + * @ingroup VEHICLELENGTH + */ + class VehicleLengthPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef VehicleLength type; + + eProsima_user_DllExport VehicleLengthPubSubType(); + + eProsima_user_DllExport virtual ~VehicleLengthPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) VehicleLength(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTH_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValue.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValue.cxx new file mode 100644 index 00000000000..8a9a1fa74a4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValue.cxx @@ -0,0 +1,189 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VehicleLengthValue.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "VehicleLengthValue.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + +etsi_its_cam_msgs::msg::VehicleLengthValue::VehicleLengthValue() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@5f212d84 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::VehicleLengthValue::~VehicleLengthValue() +{ +} + +etsi_its_cam_msgs::msg::VehicleLengthValue::VehicleLengthValue( + const VehicleLengthValue& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::VehicleLengthValue::VehicleLengthValue( + VehicleLengthValue&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::VehicleLengthValue& etsi_its_cam_msgs::msg::VehicleLengthValue::operator =( + const VehicleLengthValue& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::VehicleLengthValue& etsi_its_cam_msgs::msg::VehicleLengthValue::operator =( + VehicleLengthValue&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::VehicleLengthValue::operator ==( + const VehicleLengthValue& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::VehicleLengthValue::operator !=( + const VehicleLengthValue& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::VehicleLengthValue::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::VehicleLengthValue::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::VehicleLengthValue& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::VehicleLengthValue::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::VehicleLengthValue::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::VehicleLengthValue::value( + uint16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint16_t etsi_its_cam_msgs::msg::VehicleLengthValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint16_t& etsi_its_cam_msgs::msg::VehicleLengthValue::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::VehicleLengthValue::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::VehicleLengthValue::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::VehicleLengthValue::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValue.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValue.h new file mode 100644 index 00000000000..3fc1974de2d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValue.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VehicleLengthValue.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHVALUE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHVALUE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(VehicleLengthValue_SOURCE) +#define VehicleLengthValue_DllAPI __declspec( dllexport ) +#else +#define VehicleLengthValue_DllAPI __declspec( dllimport ) +#endif // VehicleLengthValue_SOURCE +#else +#define VehicleLengthValue_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define VehicleLengthValue_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace VehicleLengthValue_Constants { + const uint16_t MIN = 1; + const uint16_t MAX = 1023; + const uint16_t TEN_CENTIMETERS = 1; + const uint16_t OUT_OF_RANGE = 1022; + const uint16_t UNAVAILABLE = 1023; + } // namespace VehicleLengthValue_Constants + /*! + * @brief This class represents the structure VehicleLengthValue defined by the user in the IDL file. + * @ingroup VEHICLELENGTHVALUE + */ + class VehicleLengthValue + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport VehicleLengthValue(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~VehicleLengthValue(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::VehicleLengthValue that will be copied. + */ + eProsima_user_DllExport VehicleLengthValue( + const VehicleLengthValue& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::VehicleLengthValue that will be copied. + */ + eProsima_user_DllExport VehicleLengthValue( + VehicleLengthValue&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::VehicleLengthValue that will be copied. + */ + eProsima_user_DllExport VehicleLengthValue& operator =( + const VehicleLengthValue& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::VehicleLengthValue that will be copied. + */ + eProsima_user_DllExport VehicleLengthValue& operator =( + VehicleLengthValue&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::VehicleLengthValue object to compare. + */ + eProsima_user_DllExport bool operator ==( + const VehicleLengthValue& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::VehicleLengthValue object to compare. + */ + eProsima_user_DllExport bool operator !=( + const VehicleLengthValue& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint16_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint16_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint16_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::VehicleLengthValue& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint16_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHVALUE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValuePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValuePubSubTypes.cxx new file mode 100644 index 00000000000..0123f5caa87 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValuePubSubTypes.cxx @@ -0,0 +1,184 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VehicleLengthValuePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "VehicleLengthValuePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace VehicleLengthValue_Constants { + + + + + + + } //End of namespace VehicleLengthValue_Constants + VehicleLengthValuePubSubType::VehicleLengthValuePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::VehicleLengthValue_"); + auto type_size = VehicleLengthValue::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = VehicleLengthValue::isKeyDefined(); + size_t keyLength = VehicleLengthValue::getKeyMaxCdrSerializedSize() > 16 ? + VehicleLengthValue::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + VehicleLengthValuePubSubType::~VehicleLengthValuePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool VehicleLengthValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + VehicleLengthValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool VehicleLengthValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + VehicleLengthValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function VehicleLengthValuePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* VehicleLengthValuePubSubType::createData() + { + return reinterpret_cast(new VehicleLengthValue()); + } + + void VehicleLengthValuePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool VehicleLengthValuePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + VehicleLengthValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + VehicleLengthValue::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || VehicleLengthValue::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValuePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValuePubSubTypes.h new file mode 100644 index 00000000000..00923b86fe1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValuePubSubTypes.h @@ -0,0 +1,115 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VehicleLengthValuePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHVALUE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHVALUE_PUBSUBTYPES_H_ + +#include +#include + +#include "VehicleLengthValue.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated VehicleLengthValue is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace VehicleLengthValue_Constants + { + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type VehicleLengthValue defined by the user in the IDL file. + * @ingroup VEHICLELENGTHVALUE + */ + class VehicleLengthValuePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef VehicleLengthValue type; + + eProsima_user_DllExport VehicleLengthValuePubSubType(); + + eProsima_user_DllExport virtual ~VehicleLengthValuePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) VehicleLengthValue(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHVALUE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRole.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRole.cxx new file mode 100644 index 00000000000..e4f2f9b7378 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRole.cxx @@ -0,0 +1,200 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VehicleRole.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "VehicleRole.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + + + + + + + + + + + +etsi_its_cam_msgs::msg::VehicleRole::VehicleRole() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@51a06cbe + m_value = 0; + +} + +etsi_its_cam_msgs::msg::VehicleRole::~VehicleRole() +{ +} + +etsi_its_cam_msgs::msg::VehicleRole::VehicleRole( + const VehicleRole& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::VehicleRole::VehicleRole( + VehicleRole&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::VehicleRole& etsi_its_cam_msgs::msg::VehicleRole::operator =( + const VehicleRole& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::VehicleRole& etsi_its_cam_msgs::msg::VehicleRole::operator =( + VehicleRole&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::VehicleRole::operator ==( + const VehicleRole& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::VehicleRole::operator !=( + const VehicleRole& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::VehicleRole::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::VehicleRole::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::VehicleRole& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::VehicleRole::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::VehicleRole::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::VehicleRole::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::VehicleRole::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::VehicleRole::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::VehicleRole::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::VehicleRole::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::VehicleRole::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRole.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRole.h new file mode 100644 index 00000000000..030657b2f71 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRole.h @@ -0,0 +1,228 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VehicleRole.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEROLE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEROLE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(VehicleRole_SOURCE) +#define VehicleRole_DllAPI __declspec( dllexport ) +#else +#define VehicleRole_DllAPI __declspec( dllimport ) +#endif // VehicleRole_SOURCE +#else +#define VehicleRole_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define VehicleRole_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace VehicleRole_Constants { + const uint8_t DEFAULT = 0; + const uint8_t PUBLIC_TRANSPORT = 1; + const uint8_t SPECIAL_TRANSPORT = 2; + const uint8_t DANGEROUS_GOODS = 3; + const uint8_t ROAD_WORK = 4; + const uint8_t RESCUE = 5; + const uint8_t EMERGENCY = 6; + const uint8_t SAFETY_CAR = 7; + const uint8_t AGRICULTURE = 8; + const uint8_t COMMERCIAL = 9; + const uint8_t MILITARY = 10; + const uint8_t ROAD_OPERATOR = 11; + const uint8_t TAXI = 12; + const uint8_t RESERVED_1 = 13; + const uint8_t RESERVED_2 = 14; + const uint8_t RESERVED_3 = 15; + } // namespace VehicleRole_Constants + /*! + * @brief This class represents the structure VehicleRole defined by the user in the IDL file. + * @ingroup VEHICLEROLE + */ + class VehicleRole + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport VehicleRole(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~VehicleRole(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::VehicleRole that will be copied. + */ + eProsima_user_DllExport VehicleRole( + const VehicleRole& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::VehicleRole that will be copied. + */ + eProsima_user_DllExport VehicleRole( + VehicleRole&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::VehicleRole that will be copied. + */ + eProsima_user_DllExport VehicleRole& operator =( + const VehicleRole& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::VehicleRole that will be copied. + */ + eProsima_user_DllExport VehicleRole& operator =( + VehicleRole&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::VehicleRole object to compare. + */ + eProsima_user_DllExport bool operator ==( + const VehicleRole& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::VehicleRole object to compare. + */ + eProsima_user_DllExport bool operator !=( + const VehicleRole& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::VehicleRole& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEROLE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRolePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRolePubSubTypes.cxx new file mode 100644 index 00000000000..cec30c7dd14 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRolePubSubTypes.cxx @@ -0,0 +1,195 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VehicleRolePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "VehicleRolePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace VehicleRole_Constants { + + + + + + + + + + + + + + + + + + } //End of namespace VehicleRole_Constants + VehicleRolePubSubType::VehicleRolePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::VehicleRole_"); + auto type_size = VehicleRole::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = VehicleRole::isKeyDefined(); + size_t keyLength = VehicleRole::getKeyMaxCdrSerializedSize() > 16 ? + VehicleRole::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + VehicleRolePubSubType::~VehicleRolePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool VehicleRolePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + VehicleRole* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool VehicleRolePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + VehicleRole* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function VehicleRolePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* VehicleRolePubSubType::createData() + { + return reinterpret_cast(new VehicleRole()); + } + + void VehicleRolePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool VehicleRolePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + VehicleRole* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + VehicleRole::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || VehicleRole::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRolePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRolePubSubTypes.h new file mode 100644 index 00000000000..6f60c5fce1e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRolePubSubTypes.h @@ -0,0 +1,126 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VehicleRolePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEROLE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEROLE_PUBSUBTYPES_H_ + +#include +#include + +#include "VehicleRole.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated VehicleRole is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace VehicleRole_Constants + { + + + + + + + + + + + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type VehicleRole defined by the user in the IDL file. + * @ingroup VEHICLEROLE + */ + class VehicleRolePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef VehicleRole type; + + eProsima_user_DllExport VehicleRolePubSubType(); + + eProsima_user_DllExport virtual ~VehicleRolePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) VehicleRole(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEROLE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidth.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidth.cxx new file mode 100644 index 00000000000..b6e0f93b52f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidth.cxx @@ -0,0 +1,189 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VehicleWidth.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "VehicleWidth.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + +etsi_its_cam_msgs::msg::VehicleWidth::VehicleWidth() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@29d37757 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::VehicleWidth::~VehicleWidth() +{ +} + +etsi_its_cam_msgs::msg::VehicleWidth::VehicleWidth( + const VehicleWidth& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::VehicleWidth::VehicleWidth( + VehicleWidth&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::VehicleWidth& etsi_its_cam_msgs::msg::VehicleWidth::operator =( + const VehicleWidth& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::VehicleWidth& etsi_its_cam_msgs::msg::VehicleWidth::operator =( + VehicleWidth&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::VehicleWidth::operator ==( + const VehicleWidth& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::VehicleWidth::operator !=( + const VehicleWidth& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::VehicleWidth::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::VehicleWidth::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::VehicleWidth& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::VehicleWidth::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::VehicleWidth::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::VehicleWidth::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::VehicleWidth::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::VehicleWidth::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::VehicleWidth::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::VehicleWidth::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::VehicleWidth::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidth.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidth.h new file mode 100644 index 00000000000..fdcd6b7a244 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidth.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VehicleWidth.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEWIDTH_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEWIDTH_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(VehicleWidth_SOURCE) +#define VehicleWidth_DllAPI __declspec( dllexport ) +#else +#define VehicleWidth_DllAPI __declspec( dllimport ) +#endif // VehicleWidth_SOURCE +#else +#define VehicleWidth_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define VehicleWidth_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace VehicleWidth_Constants { + const uint8_t MIN = 1; + const uint8_t MAX = 62; + const uint8_t TEN_CENTIMETERS = 1; + const uint8_t OUT_OF_RANGE = 61; + const uint8_t UNAVAILABLE = 62; + } // namespace VehicleWidth_Constants + /*! + * @brief This class represents the structure VehicleWidth defined by the user in the IDL file. + * @ingroup VEHICLEWIDTH + */ + class VehicleWidth + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport VehicleWidth(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~VehicleWidth(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::VehicleWidth that will be copied. + */ + eProsima_user_DllExport VehicleWidth( + const VehicleWidth& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::VehicleWidth that will be copied. + */ + eProsima_user_DllExport VehicleWidth( + VehicleWidth&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::VehicleWidth that will be copied. + */ + eProsima_user_DllExport VehicleWidth& operator =( + const VehicleWidth& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::VehicleWidth that will be copied. + */ + eProsima_user_DllExport VehicleWidth& operator =( + VehicleWidth&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::VehicleWidth object to compare. + */ + eProsima_user_DllExport bool operator ==( + const VehicleWidth& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::VehicleWidth object to compare. + */ + eProsima_user_DllExport bool operator !=( + const VehicleWidth& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::VehicleWidth& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEWIDTH_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidthPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidthPubSubTypes.cxx new file mode 100644 index 00000000000..006e32dc819 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidthPubSubTypes.cxx @@ -0,0 +1,184 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VehicleWidthPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "VehicleWidthPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace VehicleWidth_Constants { + + + + + + + } //End of namespace VehicleWidth_Constants + VehicleWidthPubSubType::VehicleWidthPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::VehicleWidth_"); + auto type_size = VehicleWidth::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = VehicleWidth::isKeyDefined(); + size_t keyLength = VehicleWidth::getKeyMaxCdrSerializedSize() > 16 ? + VehicleWidth::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + VehicleWidthPubSubType::~VehicleWidthPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool VehicleWidthPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + VehicleWidth* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool VehicleWidthPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + VehicleWidth* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function VehicleWidthPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* VehicleWidthPubSubType::createData() + { + return reinterpret_cast(new VehicleWidth()); + } + + void VehicleWidthPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool VehicleWidthPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + VehicleWidth* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + VehicleWidth::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || VehicleWidth::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidthPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidthPubSubTypes.h new file mode 100644 index 00000000000..fbeb1df502c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidthPubSubTypes.h @@ -0,0 +1,115 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VehicleWidthPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEWIDTH_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEWIDTH_PUBSUBTYPES_H_ + +#include +#include + +#include "VehicleWidth.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated VehicleWidth is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace VehicleWidth_Constants + { + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type VehicleWidth defined by the user in the IDL file. + * @ingroup VEHICLEWIDTH + */ + class VehicleWidthPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef VehicleWidth type; + + eProsima_user_DllExport VehicleWidthPubSubType(); + + eProsima_user_DllExport virtual ~VehicleWidthPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) VehicleWidth(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEWIDTH_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAcceleration.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAcceleration.cxx new file mode 100644 index 00000000000..c384c790c1d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAcceleration.cxx @@ -0,0 +1,238 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VerticalAcceleration.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "VerticalAcceleration.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::VerticalAcceleration::VerticalAcceleration() +{ + // m_vertical_acceleration_value com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@6e4ea0bd + + // m_vertical_acceleration_confidence com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@56f2bbea + + +} + +etsi_its_cam_msgs::msg::VerticalAcceleration::~VerticalAcceleration() +{ + +} + +etsi_its_cam_msgs::msg::VerticalAcceleration::VerticalAcceleration( + const VerticalAcceleration& x) +{ + m_vertical_acceleration_value = x.m_vertical_acceleration_value; + m_vertical_acceleration_confidence = x.m_vertical_acceleration_confidence; +} + +etsi_its_cam_msgs::msg::VerticalAcceleration::VerticalAcceleration( + VerticalAcceleration&& x) +{ + m_vertical_acceleration_value = std::move(x.m_vertical_acceleration_value); + m_vertical_acceleration_confidence = std::move(x.m_vertical_acceleration_confidence); +} + +etsi_its_cam_msgs::msg::VerticalAcceleration& etsi_its_cam_msgs::msg::VerticalAcceleration::operator =( + const VerticalAcceleration& x) +{ + + m_vertical_acceleration_value = x.m_vertical_acceleration_value; + m_vertical_acceleration_confidence = x.m_vertical_acceleration_confidence; + + return *this; +} + +etsi_its_cam_msgs::msg::VerticalAcceleration& etsi_its_cam_msgs::msg::VerticalAcceleration::operator =( + VerticalAcceleration&& x) +{ + + m_vertical_acceleration_value = std::move(x.m_vertical_acceleration_value); + m_vertical_acceleration_confidence = std::move(x.m_vertical_acceleration_confidence); + + return *this; +} + +bool etsi_its_cam_msgs::msg::VerticalAcceleration::operator ==( + const VerticalAcceleration& x) const +{ + + return (m_vertical_acceleration_value == x.m_vertical_acceleration_value && m_vertical_acceleration_confidence == x.m_vertical_acceleration_confidence); +} + +bool etsi_its_cam_msgs::msg::VerticalAcceleration::operator !=( + const VerticalAcceleration& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::VerticalAcceleration::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::VerticalAccelerationValue::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::AccelerationConfidence::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::VerticalAcceleration::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::VerticalAcceleration& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::VerticalAccelerationValue::getCdrSerializedSize(data.vertical_acceleration_value(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::AccelerationConfidence::getCdrSerializedSize(data.vertical_acceleration_confidence(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::VerticalAcceleration::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_vertical_acceleration_value; + scdr << m_vertical_acceleration_confidence; + +} + +void etsi_its_cam_msgs::msg::VerticalAcceleration::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_vertical_acceleration_value; + dcdr >> m_vertical_acceleration_confidence; +} + +/*! + * @brief This function copies the value in member vertical_acceleration_value + * @param _vertical_acceleration_value New value to be copied in member vertical_acceleration_value + */ +void etsi_its_cam_msgs::msg::VerticalAcceleration::vertical_acceleration_value( + const etsi_its_cam_msgs::msg::VerticalAccelerationValue& _vertical_acceleration_value) +{ + m_vertical_acceleration_value = _vertical_acceleration_value; +} + +/*! + * @brief This function moves the value in member vertical_acceleration_value + * @param _vertical_acceleration_value New value to be moved in member vertical_acceleration_value + */ +void etsi_its_cam_msgs::msg::VerticalAcceleration::vertical_acceleration_value( + etsi_its_cam_msgs::msg::VerticalAccelerationValue&& _vertical_acceleration_value) +{ + m_vertical_acceleration_value = std::move(_vertical_acceleration_value); +} + +/*! + * @brief This function returns a constant reference to member vertical_acceleration_value + * @return Constant reference to member vertical_acceleration_value + */ +const etsi_its_cam_msgs::msg::VerticalAccelerationValue& etsi_its_cam_msgs::msg::VerticalAcceleration::vertical_acceleration_value() const +{ + return m_vertical_acceleration_value; +} + +/*! + * @brief This function returns a reference to member vertical_acceleration_value + * @return Reference to member vertical_acceleration_value + */ +etsi_its_cam_msgs::msg::VerticalAccelerationValue& etsi_its_cam_msgs::msg::VerticalAcceleration::vertical_acceleration_value() +{ + return m_vertical_acceleration_value; +} +/*! + * @brief This function copies the value in member vertical_acceleration_confidence + * @param _vertical_acceleration_confidence New value to be copied in member vertical_acceleration_confidence + */ +void etsi_its_cam_msgs::msg::VerticalAcceleration::vertical_acceleration_confidence( + const etsi_its_cam_msgs::msg::AccelerationConfidence& _vertical_acceleration_confidence) +{ + m_vertical_acceleration_confidence = _vertical_acceleration_confidence; +} + +/*! + * @brief This function moves the value in member vertical_acceleration_confidence + * @param _vertical_acceleration_confidence New value to be moved in member vertical_acceleration_confidence + */ +void etsi_its_cam_msgs::msg::VerticalAcceleration::vertical_acceleration_confidence( + etsi_its_cam_msgs::msg::AccelerationConfidence&& _vertical_acceleration_confidence) +{ + m_vertical_acceleration_confidence = std::move(_vertical_acceleration_confidence); +} + +/*! + * @brief This function returns a constant reference to member vertical_acceleration_confidence + * @return Constant reference to member vertical_acceleration_confidence + */ +const etsi_its_cam_msgs::msg::AccelerationConfidence& etsi_its_cam_msgs::msg::VerticalAcceleration::vertical_acceleration_confidence() const +{ + return m_vertical_acceleration_confidence; +} + +/*! + * @brief This function returns a reference to member vertical_acceleration_confidence + * @return Reference to member vertical_acceleration_confidence + */ +etsi_its_cam_msgs::msg::AccelerationConfidence& etsi_its_cam_msgs::msg::VerticalAcceleration::vertical_acceleration_confidence() +{ + return m_vertical_acceleration_confidence; +} + +size_t etsi_its_cam_msgs::msg::VerticalAcceleration::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::VerticalAcceleration::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::VerticalAcceleration::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAcceleration.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAcceleration.h new file mode 100644 index 00000000000..0d256bb7d7c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAcceleration.h @@ -0,0 +1,244 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VerticalAcceleration.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATION_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATION_H_ + +#include "AccelerationConfidence.h" +#include "VerticalAccelerationValue.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(VerticalAcceleration_SOURCE) +#define VerticalAcceleration_DllAPI __declspec( dllexport ) +#else +#define VerticalAcceleration_DllAPI __declspec( dllimport ) +#endif // VerticalAcceleration_SOURCE +#else +#define VerticalAcceleration_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define VerticalAcceleration_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure VerticalAcceleration defined by the user in the IDL file. + * @ingroup VERTICALACCELERATION + */ + class VerticalAcceleration + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport VerticalAcceleration(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~VerticalAcceleration(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::VerticalAcceleration that will be copied. + */ + eProsima_user_DllExport VerticalAcceleration( + const VerticalAcceleration& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::VerticalAcceleration that will be copied. + */ + eProsima_user_DllExport VerticalAcceleration( + VerticalAcceleration&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::VerticalAcceleration that will be copied. + */ + eProsima_user_DllExport VerticalAcceleration& operator =( + const VerticalAcceleration& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::VerticalAcceleration that will be copied. + */ + eProsima_user_DllExport VerticalAcceleration& operator =( + VerticalAcceleration&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::VerticalAcceleration object to compare. + */ + eProsima_user_DllExport bool operator ==( + const VerticalAcceleration& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::VerticalAcceleration object to compare. + */ + eProsima_user_DllExport bool operator !=( + const VerticalAcceleration& x) const; + + /*! + * @brief This function copies the value in member vertical_acceleration_value + * @param _vertical_acceleration_value New value to be copied in member vertical_acceleration_value + */ + eProsima_user_DllExport void vertical_acceleration_value( + const etsi_its_cam_msgs::msg::VerticalAccelerationValue& _vertical_acceleration_value); + + /*! + * @brief This function moves the value in member vertical_acceleration_value + * @param _vertical_acceleration_value New value to be moved in member vertical_acceleration_value + */ + eProsima_user_DllExport void vertical_acceleration_value( + etsi_its_cam_msgs::msg::VerticalAccelerationValue&& _vertical_acceleration_value); + + /*! + * @brief This function returns a constant reference to member vertical_acceleration_value + * @return Constant reference to member vertical_acceleration_value + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::VerticalAccelerationValue& vertical_acceleration_value() const; + + /*! + * @brief This function returns a reference to member vertical_acceleration_value + * @return Reference to member vertical_acceleration_value + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::VerticalAccelerationValue& vertical_acceleration_value(); + /*! + * @brief This function copies the value in member vertical_acceleration_confidence + * @param _vertical_acceleration_confidence New value to be copied in member vertical_acceleration_confidence + */ + eProsima_user_DllExport void vertical_acceleration_confidence( + const etsi_its_cam_msgs::msg::AccelerationConfidence& _vertical_acceleration_confidence); + + /*! + * @brief This function moves the value in member vertical_acceleration_confidence + * @param _vertical_acceleration_confidence New value to be moved in member vertical_acceleration_confidence + */ + eProsima_user_DllExport void vertical_acceleration_confidence( + etsi_its_cam_msgs::msg::AccelerationConfidence&& _vertical_acceleration_confidence); + + /*! + * @brief This function returns a constant reference to member vertical_acceleration_confidence + * @return Constant reference to member vertical_acceleration_confidence + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::AccelerationConfidence& vertical_acceleration_confidence() const; + + /*! + * @brief This function returns a reference to member vertical_acceleration_confidence + * @return Reference to member vertical_acceleration_confidence + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::AccelerationConfidence& vertical_acceleration_confidence(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::VerticalAcceleration& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::VerticalAccelerationValue m_vertical_acceleration_value; + etsi_its_cam_msgs::msg::AccelerationConfidence m_vertical_acceleration_confidence; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATION_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationPubSubTypes.cxx new file mode 100644 index 00000000000..641e64c0966 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VerticalAccelerationPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "VerticalAccelerationPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + VerticalAccelerationPubSubType::VerticalAccelerationPubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::VerticalAcceleration_"); + auto type_size = VerticalAcceleration::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = VerticalAcceleration::isKeyDefined(); + size_t keyLength = VerticalAcceleration::getKeyMaxCdrSerializedSize() > 16 ? + VerticalAcceleration::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + VerticalAccelerationPubSubType::~VerticalAccelerationPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool VerticalAccelerationPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + VerticalAcceleration* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool VerticalAccelerationPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + VerticalAcceleration* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function VerticalAccelerationPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* VerticalAccelerationPubSubType::createData() + { + return reinterpret_cast(new VerticalAcceleration()); + } + + void VerticalAccelerationPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool VerticalAccelerationPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + VerticalAcceleration* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + VerticalAcceleration::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || VerticalAcceleration::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationPubSubTypes.h new file mode 100644 index 00000000000..7d48f81ee84 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VerticalAccelerationPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATION_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATION_PUBSUBTYPES_H_ + +#include +#include + +#include "VerticalAcceleration.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated VerticalAcceleration is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type VerticalAcceleration defined by the user in the IDL file. + * @ingroup VERTICALACCELERATION + */ + class VerticalAccelerationPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef VerticalAcceleration type; + + eProsima_user_DllExport VerticalAccelerationPubSubType(); + + eProsima_user_DllExport virtual ~VerticalAccelerationPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) VerticalAcceleration(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATION_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValue.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValue.cxx new file mode 100644 index 00000000000..b42614299c2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValue.cxx @@ -0,0 +1,189 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VerticalAccelerationValue.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "VerticalAccelerationValue.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + +etsi_its_cam_msgs::msg::VerticalAccelerationValue::VerticalAccelerationValue() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@1e411d81 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::VerticalAccelerationValue::~VerticalAccelerationValue() +{ +} + +etsi_its_cam_msgs::msg::VerticalAccelerationValue::VerticalAccelerationValue( + const VerticalAccelerationValue& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::VerticalAccelerationValue::VerticalAccelerationValue( + VerticalAccelerationValue&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::VerticalAccelerationValue& etsi_its_cam_msgs::msg::VerticalAccelerationValue::operator =( + const VerticalAccelerationValue& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::VerticalAccelerationValue& etsi_its_cam_msgs::msg::VerticalAccelerationValue::operator =( + VerticalAccelerationValue&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::VerticalAccelerationValue::operator ==( + const VerticalAccelerationValue& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::VerticalAccelerationValue::operator !=( + const VerticalAccelerationValue& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::VerticalAccelerationValue::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::VerticalAccelerationValue::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::VerticalAccelerationValue& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::VerticalAccelerationValue::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::VerticalAccelerationValue::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::VerticalAccelerationValue::value( + int16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int16_t etsi_its_cam_msgs::msg::VerticalAccelerationValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int16_t& etsi_its_cam_msgs::msg::VerticalAccelerationValue::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::VerticalAccelerationValue::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::VerticalAccelerationValue::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::VerticalAccelerationValue::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValue.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValue.h new file mode 100644 index 00000000000..7d547cafde5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValue.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VerticalAccelerationValue.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATIONVALUE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATIONVALUE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(VerticalAccelerationValue_SOURCE) +#define VerticalAccelerationValue_DllAPI __declspec( dllexport ) +#else +#define VerticalAccelerationValue_DllAPI __declspec( dllimport ) +#endif // VerticalAccelerationValue_SOURCE +#else +#define VerticalAccelerationValue_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define VerticalAccelerationValue_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace VerticalAccelerationValue_Constants { + const int16_t MIN = -160; + const int16_t MAX = 161; + const int16_t POINT_ONE_METER_PER_SEC_SQUARED_UP = 1; + const int16_t POINT_ONE_METER_PER_SEC_SQUARED_DOWN = -1; + const int16_t UNAVAILABLE = 161; + } // namespace VerticalAccelerationValue_Constants + /*! + * @brief This class represents the structure VerticalAccelerationValue defined by the user in the IDL file. + * @ingroup VERTICALACCELERATIONVALUE + */ + class VerticalAccelerationValue + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport VerticalAccelerationValue(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~VerticalAccelerationValue(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::VerticalAccelerationValue that will be copied. + */ + eProsima_user_DllExport VerticalAccelerationValue( + const VerticalAccelerationValue& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::VerticalAccelerationValue that will be copied. + */ + eProsima_user_DllExport VerticalAccelerationValue( + VerticalAccelerationValue&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::VerticalAccelerationValue that will be copied. + */ + eProsima_user_DllExport VerticalAccelerationValue& operator =( + const VerticalAccelerationValue& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::VerticalAccelerationValue that will be copied. + */ + eProsima_user_DllExport VerticalAccelerationValue& operator =( + VerticalAccelerationValue&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::VerticalAccelerationValue object to compare. + */ + eProsima_user_DllExport bool operator ==( + const VerticalAccelerationValue& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::VerticalAccelerationValue object to compare. + */ + eProsima_user_DllExport bool operator !=( + const VerticalAccelerationValue& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + int16_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport int16_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport int16_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::VerticalAccelerationValue& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + int16_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATIONVALUE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValuePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValuePubSubTypes.cxx new file mode 100644 index 00000000000..57fc138db1d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValuePubSubTypes.cxx @@ -0,0 +1,184 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VerticalAccelerationValuePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "VerticalAccelerationValuePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace VerticalAccelerationValue_Constants { + + + + + + + } //End of namespace VerticalAccelerationValue_Constants + VerticalAccelerationValuePubSubType::VerticalAccelerationValuePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::VerticalAccelerationValue_"); + auto type_size = VerticalAccelerationValue::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = VerticalAccelerationValue::isKeyDefined(); + size_t keyLength = VerticalAccelerationValue::getKeyMaxCdrSerializedSize() > 16 ? + VerticalAccelerationValue::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + VerticalAccelerationValuePubSubType::~VerticalAccelerationValuePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool VerticalAccelerationValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + VerticalAccelerationValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool VerticalAccelerationValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + VerticalAccelerationValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function VerticalAccelerationValuePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* VerticalAccelerationValuePubSubType::createData() + { + return reinterpret_cast(new VerticalAccelerationValue()); + } + + void VerticalAccelerationValuePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool VerticalAccelerationValuePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + VerticalAccelerationValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + VerticalAccelerationValue::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || VerticalAccelerationValue::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValuePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValuePubSubTypes.h new file mode 100644 index 00000000000..217790a0fc6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValuePubSubTypes.h @@ -0,0 +1,115 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file VerticalAccelerationValuePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATIONVALUE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATIONVALUE_PUBSUBTYPES_H_ + +#include +#include + +#include "VerticalAccelerationValue.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated VerticalAccelerationValue is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace VerticalAccelerationValue_Constants + { + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type VerticalAccelerationValue defined by the user in the IDL file. + * @ingroup VERTICALACCELERATIONVALUE + */ + class VerticalAccelerationValuePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef VerticalAccelerationValue type; + + eProsima_user_DllExport VerticalAccelerationValuePubSubType(); + + eProsima_user_DllExport virtual ~VerticalAccelerationValuePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) VerticalAccelerationValue(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATIONVALUE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRate.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRate.cxx new file mode 100644 index 00000000000..4a061f251d6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRate.cxx @@ -0,0 +1,238 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file YawRate.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "YawRate.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +etsi_its_cam_msgs::msg::YawRate::YawRate() +{ + // m_yaw_rate_value com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@1654a892 + + // m_yaw_rate_confidence com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@2577d6c8 + + +} + +etsi_its_cam_msgs::msg::YawRate::~YawRate() +{ + +} + +etsi_its_cam_msgs::msg::YawRate::YawRate( + const YawRate& x) +{ + m_yaw_rate_value = x.m_yaw_rate_value; + m_yaw_rate_confidence = x.m_yaw_rate_confidence; +} + +etsi_its_cam_msgs::msg::YawRate::YawRate( + YawRate&& x) +{ + m_yaw_rate_value = std::move(x.m_yaw_rate_value); + m_yaw_rate_confidence = std::move(x.m_yaw_rate_confidence); +} + +etsi_its_cam_msgs::msg::YawRate& etsi_its_cam_msgs::msg::YawRate::operator =( + const YawRate& x) +{ + + m_yaw_rate_value = x.m_yaw_rate_value; + m_yaw_rate_confidence = x.m_yaw_rate_confidence; + + return *this; +} + +etsi_its_cam_msgs::msg::YawRate& etsi_its_cam_msgs::msg::YawRate::operator =( + YawRate&& x) +{ + + m_yaw_rate_value = std::move(x.m_yaw_rate_value); + m_yaw_rate_confidence = std::move(x.m_yaw_rate_confidence); + + return *this; +} + +bool etsi_its_cam_msgs::msg::YawRate::operator ==( + const YawRate& x) const +{ + + return (m_yaw_rate_value == x.m_yaw_rate_value && m_yaw_rate_confidence == x.m_yaw_rate_confidence); +} + +bool etsi_its_cam_msgs::msg::YawRate::operator !=( + const YawRate& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::YawRate::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::YawRateValue::getMaxCdrSerializedSize(current_alignment); + current_alignment += etsi_its_cam_msgs::msg::YawRateConfidence::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::YawRate::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::YawRate& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += etsi_its_cam_msgs::msg::YawRateValue::getCdrSerializedSize(data.yaw_rate_value(), current_alignment); + current_alignment += etsi_its_cam_msgs::msg::YawRateConfidence::getCdrSerializedSize(data.yaw_rate_confidence(), current_alignment); + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::YawRate::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_yaw_rate_value; + scdr << m_yaw_rate_confidence; + +} + +void etsi_its_cam_msgs::msg::YawRate::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_yaw_rate_value; + dcdr >> m_yaw_rate_confidence; +} + +/*! + * @brief This function copies the value in member yaw_rate_value + * @param _yaw_rate_value New value to be copied in member yaw_rate_value + */ +void etsi_its_cam_msgs::msg::YawRate::yaw_rate_value( + const etsi_its_cam_msgs::msg::YawRateValue& _yaw_rate_value) +{ + m_yaw_rate_value = _yaw_rate_value; +} + +/*! + * @brief This function moves the value in member yaw_rate_value + * @param _yaw_rate_value New value to be moved in member yaw_rate_value + */ +void etsi_its_cam_msgs::msg::YawRate::yaw_rate_value( + etsi_its_cam_msgs::msg::YawRateValue&& _yaw_rate_value) +{ + m_yaw_rate_value = std::move(_yaw_rate_value); +} + +/*! + * @brief This function returns a constant reference to member yaw_rate_value + * @return Constant reference to member yaw_rate_value + */ +const etsi_its_cam_msgs::msg::YawRateValue& etsi_its_cam_msgs::msg::YawRate::yaw_rate_value() const +{ + return m_yaw_rate_value; +} + +/*! + * @brief This function returns a reference to member yaw_rate_value + * @return Reference to member yaw_rate_value + */ +etsi_its_cam_msgs::msg::YawRateValue& etsi_its_cam_msgs::msg::YawRate::yaw_rate_value() +{ + return m_yaw_rate_value; +} +/*! + * @brief This function copies the value in member yaw_rate_confidence + * @param _yaw_rate_confidence New value to be copied in member yaw_rate_confidence + */ +void etsi_its_cam_msgs::msg::YawRate::yaw_rate_confidence( + const etsi_its_cam_msgs::msg::YawRateConfidence& _yaw_rate_confidence) +{ + m_yaw_rate_confidence = _yaw_rate_confidence; +} + +/*! + * @brief This function moves the value in member yaw_rate_confidence + * @param _yaw_rate_confidence New value to be moved in member yaw_rate_confidence + */ +void etsi_its_cam_msgs::msg::YawRate::yaw_rate_confidence( + etsi_its_cam_msgs::msg::YawRateConfidence&& _yaw_rate_confidence) +{ + m_yaw_rate_confidence = std::move(_yaw_rate_confidence); +} + +/*! + * @brief This function returns a constant reference to member yaw_rate_confidence + * @return Constant reference to member yaw_rate_confidence + */ +const etsi_its_cam_msgs::msg::YawRateConfidence& etsi_its_cam_msgs::msg::YawRate::yaw_rate_confidence() const +{ + return m_yaw_rate_confidence; +} + +/*! + * @brief This function returns a reference to member yaw_rate_confidence + * @return Reference to member yaw_rate_confidence + */ +etsi_its_cam_msgs::msg::YawRateConfidence& etsi_its_cam_msgs::msg::YawRate::yaw_rate_confidence() +{ + return m_yaw_rate_confidence; +} + +size_t etsi_its_cam_msgs::msg::YawRate::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::YawRate::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::YawRate::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRate.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRate.h new file mode 100644 index 00000000000..fd230133b32 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRate.h @@ -0,0 +1,244 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file YawRate.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATE_H_ + +#include "YawRateConfidence.h" +#include "YawRateValue.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(YawRate_SOURCE) +#define YawRate_DllAPI __declspec( dllexport ) +#else +#define YawRate_DllAPI __declspec( dllimport ) +#endif // YawRate_SOURCE +#else +#define YawRate_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define YawRate_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + /*! + * @brief This class represents the structure YawRate defined by the user in the IDL file. + * @ingroup YAWRATE + */ + class YawRate + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport YawRate(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~YawRate(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::YawRate that will be copied. + */ + eProsima_user_DllExport YawRate( + const YawRate& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::YawRate that will be copied. + */ + eProsima_user_DllExport YawRate( + YawRate&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::YawRate that will be copied. + */ + eProsima_user_DllExport YawRate& operator =( + const YawRate& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::YawRate that will be copied. + */ + eProsima_user_DllExport YawRate& operator =( + YawRate&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::YawRate object to compare. + */ + eProsima_user_DllExport bool operator ==( + const YawRate& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::YawRate object to compare. + */ + eProsima_user_DllExport bool operator !=( + const YawRate& x) const; + + /*! + * @brief This function copies the value in member yaw_rate_value + * @param _yaw_rate_value New value to be copied in member yaw_rate_value + */ + eProsima_user_DllExport void yaw_rate_value( + const etsi_its_cam_msgs::msg::YawRateValue& _yaw_rate_value); + + /*! + * @brief This function moves the value in member yaw_rate_value + * @param _yaw_rate_value New value to be moved in member yaw_rate_value + */ + eProsima_user_DllExport void yaw_rate_value( + etsi_its_cam_msgs::msg::YawRateValue&& _yaw_rate_value); + + /*! + * @brief This function returns a constant reference to member yaw_rate_value + * @return Constant reference to member yaw_rate_value + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::YawRateValue& yaw_rate_value() const; + + /*! + * @brief This function returns a reference to member yaw_rate_value + * @return Reference to member yaw_rate_value + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::YawRateValue& yaw_rate_value(); + /*! + * @brief This function copies the value in member yaw_rate_confidence + * @param _yaw_rate_confidence New value to be copied in member yaw_rate_confidence + */ + eProsima_user_DllExport void yaw_rate_confidence( + const etsi_its_cam_msgs::msg::YawRateConfidence& _yaw_rate_confidence); + + /*! + * @brief This function moves the value in member yaw_rate_confidence + * @param _yaw_rate_confidence New value to be moved in member yaw_rate_confidence + */ + eProsima_user_DllExport void yaw_rate_confidence( + etsi_its_cam_msgs::msg::YawRateConfidence&& _yaw_rate_confidence); + + /*! + * @brief This function returns a constant reference to member yaw_rate_confidence + * @return Constant reference to member yaw_rate_confidence + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::YawRateConfidence& yaw_rate_confidence() const; + + /*! + * @brief This function returns a reference to member yaw_rate_confidence + * @return Reference to member yaw_rate_confidence + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::YawRateConfidence& yaw_rate_confidence(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::YawRate& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + etsi_its_cam_msgs::msg::YawRateValue m_yaw_rate_value; + etsi_its_cam_msgs::msg::YawRateConfidence m_yaw_rate_confidence; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidence.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidence.cxx new file mode 100644 index 00000000000..a6e6e176577 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidence.cxx @@ -0,0 +1,193 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file YawRateConfidence.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "YawRateConfidence.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + + + + +etsi_its_cam_msgs::msg::YawRateConfidence::YawRateConfidence() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@654c1a54 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::YawRateConfidence::~YawRateConfidence() +{ +} + +etsi_its_cam_msgs::msg::YawRateConfidence::YawRateConfidence( + const YawRateConfidence& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::YawRateConfidence::YawRateConfidence( + YawRateConfidence&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::YawRateConfidence& etsi_its_cam_msgs::msg::YawRateConfidence::operator =( + const YawRateConfidence& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::YawRateConfidence& etsi_its_cam_msgs::msg::YawRateConfidence::operator =( + YawRateConfidence&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::YawRateConfidence::operator ==( + const YawRateConfidence& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::YawRateConfidence::operator !=( + const YawRateConfidence& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::YawRateConfidence::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::YawRateConfidence::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::YawRateConfidence& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::YawRateConfidence::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::YawRateConfidence::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::YawRateConfidence::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t etsi_its_cam_msgs::msg::YawRateConfidence::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& etsi_its_cam_msgs::msg::YawRateConfidence::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::YawRateConfidence::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::YawRateConfidence::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::YawRateConfidence::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidence.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidence.h new file mode 100644 index 00000000000..6f9b788e944 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidence.h @@ -0,0 +1,221 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file YawRateConfidence.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATECONFIDENCE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATECONFIDENCE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(YawRateConfidence_SOURCE) +#define YawRateConfidence_DllAPI __declspec( dllexport ) +#else +#define YawRateConfidence_DllAPI __declspec( dllimport ) +#endif // YawRateConfidence_SOURCE +#else +#define YawRateConfidence_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define YawRateConfidence_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace YawRateConfidence_Constants { + const uint8_t DEG_SEC_000_01 = 0; + const uint8_t DEG_SEC_000_05 = 1; + const uint8_t DEG_SEC_000_10 = 2; + const uint8_t DEG_SEC_001_00 = 3; + const uint8_t DEG_SEC_005_00 = 4; + const uint8_t DEG_SEC_010_00 = 5; + const uint8_t DEG_SEC_100_00 = 6; + const uint8_t OUT_OF_RANGE = 7; + const uint8_t UNAVAILABLE = 8; + } // namespace YawRateConfidence_Constants + /*! + * @brief This class represents the structure YawRateConfidence defined by the user in the IDL file. + * @ingroup YAWRATECONFIDENCE + */ + class YawRateConfidence + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport YawRateConfidence(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~YawRateConfidence(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::YawRateConfidence that will be copied. + */ + eProsima_user_DllExport YawRateConfidence( + const YawRateConfidence& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::YawRateConfidence that will be copied. + */ + eProsima_user_DllExport YawRateConfidence( + YawRateConfidence&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::YawRateConfidence that will be copied. + */ + eProsima_user_DllExport YawRateConfidence& operator =( + const YawRateConfidence& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::YawRateConfidence that will be copied. + */ + eProsima_user_DllExport YawRateConfidence& operator =( + YawRateConfidence&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::YawRateConfidence object to compare. + */ + eProsima_user_DllExport bool operator ==( + const YawRateConfidence& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::YawRateConfidence object to compare. + */ + eProsima_user_DllExport bool operator !=( + const YawRateConfidence& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + uint8_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport uint8_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport uint8_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::YawRateConfidence& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + uint8_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATECONFIDENCE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidencePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidencePubSubTypes.cxx new file mode 100644 index 00000000000..e987bf872ca --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidencePubSubTypes.cxx @@ -0,0 +1,188 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file YawRateConfidencePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "YawRateConfidencePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace YawRateConfidence_Constants { + + + + + + + + + + + } //End of namespace YawRateConfidence_Constants + YawRateConfidencePubSubType::YawRateConfidencePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::YawRateConfidence_"); + auto type_size = YawRateConfidence::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = YawRateConfidence::isKeyDefined(); + size_t keyLength = YawRateConfidence::getKeyMaxCdrSerializedSize() > 16 ? + YawRateConfidence::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + YawRateConfidencePubSubType::~YawRateConfidencePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool YawRateConfidencePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + YawRateConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool YawRateConfidencePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + YawRateConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function YawRateConfidencePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* YawRateConfidencePubSubType::createData() + { + return reinterpret_cast(new YawRateConfidence()); + } + + void YawRateConfidencePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool YawRateConfidencePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + YawRateConfidence* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + YawRateConfidence::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || YawRateConfidence::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidencePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidencePubSubTypes.h new file mode 100644 index 00000000000..cbf8227f0a6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidencePubSubTypes.h @@ -0,0 +1,119 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file YawRateConfidencePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATECONFIDENCE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATECONFIDENCE_PUBSUBTYPES_H_ + +#include +#include + +#include "YawRateConfidence.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated YawRateConfidence is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace YawRateConfidence_Constants + { + + + + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type YawRateConfidence defined by the user in the IDL file. + * @ingroup YAWRATECONFIDENCE + */ + class YawRateConfidencePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef YawRateConfidence type; + + eProsima_user_DllExport YawRateConfidencePubSubType(); + + eProsima_user_DllExport virtual ~YawRateConfidencePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) YawRateConfidence(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATECONFIDENCE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRatePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRatePubSubTypes.cxx new file mode 100644 index 00000000000..b0bca8db5da --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRatePubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file YawRatePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "YawRatePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + YawRatePubSubType::YawRatePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::YawRate_"); + auto type_size = YawRate::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = YawRate::isKeyDefined(); + size_t keyLength = YawRate::getKeyMaxCdrSerializedSize() > 16 ? + YawRate::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + YawRatePubSubType::~YawRatePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool YawRatePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + YawRate* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool YawRatePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + YawRate* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function YawRatePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* YawRatePubSubType::createData() + { + return reinterpret_cast(new YawRate()); + } + + void YawRatePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool YawRatePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + YawRate* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + YawRate::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || YawRate::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRatePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRatePubSubTypes.h new file mode 100644 index 00000000000..7f1e2ba702f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRatePubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file YawRatePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATE_PUBSUBTYPES_H_ + +#include +#include + +#include "YawRate.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated YawRate is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type YawRate defined by the user in the IDL file. + * @ingroup YAWRATE + */ + class YawRatePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef YawRate type; + + eProsima_user_DllExport YawRatePubSubType(); + + eProsima_user_DllExport virtual ~YawRatePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) YawRate(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValue.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValue.cxx new file mode 100644 index 00000000000..d775473d2a2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValue.cxx @@ -0,0 +1,190 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file YawRateValue.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "YawRateValue.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + +etsi_its_cam_msgs::msg::YawRateValue::YawRateValue() +{ + // m_value com.eprosima.idl.parser.typecode.PrimitiveTypeCode@1adb7478 + m_value = 0; + +} + +etsi_its_cam_msgs::msg::YawRateValue::~YawRateValue() +{ +} + +etsi_its_cam_msgs::msg::YawRateValue::YawRateValue( + const YawRateValue& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::YawRateValue::YawRateValue( + YawRateValue&& x) +{ + m_value = x.m_value; +} + +etsi_its_cam_msgs::msg::YawRateValue& etsi_its_cam_msgs::msg::YawRateValue::operator =( + const YawRateValue& x) +{ + + m_value = x.m_value; + + return *this; +} + +etsi_its_cam_msgs::msg::YawRateValue& etsi_its_cam_msgs::msg::YawRateValue::operator =( + YawRateValue&& x) +{ + + m_value = x.m_value; + + return *this; +} + +bool etsi_its_cam_msgs::msg::YawRateValue::operator ==( + const YawRateValue& x) const +{ + + return (m_value == x.m_value); +} + +bool etsi_its_cam_msgs::msg::YawRateValue::operator !=( + const YawRateValue& x) const +{ + return !(*this == x); +} + +size_t etsi_its_cam_msgs::msg::YawRateValue::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +size_t etsi_its_cam_msgs::msg::YawRateValue::getCdrSerializedSize( + const etsi_its_cam_msgs::msg::YawRateValue& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); + + + return current_alignment - initial_alignment; +} + +void etsi_its_cam_msgs::msg::YawRateValue::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_value; + +} + +void etsi_its_cam_msgs::msg::YawRateValue::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_value; +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void etsi_its_cam_msgs::msg::YawRateValue::value( + int16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int16_t etsi_its_cam_msgs::msg::YawRateValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int16_t& etsi_its_cam_msgs::msg::YawRateValue::value() +{ + return m_value; +} + + +size_t etsi_its_cam_msgs::msg::YawRateValue::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool etsi_its_cam_msgs::msg::YawRateValue::isKeyDefined() +{ + return false; +} + +void etsi_its_cam_msgs::msg::YawRateValue::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValue.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValue.h new file mode 100644 index 00000000000..52b3fbbcc9f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValue.h @@ -0,0 +1,218 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file YawRateValue.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATEVALUE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATEVALUE_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(YawRateValue_SOURCE) +#define YawRateValue_DllAPI __declspec( dllexport ) +#else +#define YawRateValue_DllAPI __declspec( dllimport ) +#endif // YawRateValue_SOURCE +#else +#define YawRateValue_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define YawRateValue_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace etsi_its_cam_msgs { + namespace msg { + namespace YawRateValue_Constants { + const int16_t MIN = -32766; + const int16_t MAX = 32767; + const int16_t STRAIGHT = 0; + const int16_t DEG_SEC_000_01_TO_RIGHT = -1; + const int16_t DEG_SEC_000_01_TO_LEFT = 1; + const int16_t UNAVAILABLE = 32767; + } // namespace YawRateValue_Constants + /*! + * @brief This class represents the structure YawRateValue defined by the user in the IDL file. + * @ingroup YAWRATEVALUE + */ + class YawRateValue + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport YawRateValue(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~YawRateValue(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::YawRateValue that will be copied. + */ + eProsima_user_DllExport YawRateValue( + const YawRateValue& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::YawRateValue that will be copied. + */ + eProsima_user_DllExport YawRateValue( + YawRateValue&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::YawRateValue that will be copied. + */ + eProsima_user_DllExport YawRateValue& operator =( + const YawRateValue& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::YawRateValue that will be copied. + */ + eProsima_user_DllExport YawRateValue& operator =( + YawRateValue&& x); + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::YawRateValue object to compare. + */ + eProsima_user_DllExport bool operator ==( + const YawRateValue& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::YawRateValue object to compare. + */ + eProsima_user_DllExport bool operator !=( + const YawRateValue& x) const; + + /*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ + eProsima_user_DllExport void value( + int16_t _value); + + /*! + * @brief This function returns the value of member value + * @return Value of member value + */ + eProsima_user_DllExport int16_t value() const; + + /*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ + eProsima_user_DllExport int16_t& value(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const etsi_its_cam_msgs::msg::YawRateValue& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + int16_t m_value; + }; + } // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATEVALUE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValuePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValuePubSubTypes.cxx new file mode 100644 index 00000000000..9769e0d6495 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValuePubSubTypes.cxx @@ -0,0 +1,185 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file YawRateValuePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "YawRateValuePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace etsi_its_cam_msgs { + namespace msg { + namespace YawRateValue_Constants { + + + + + + + + } //End of namespace YawRateValue_Constants + YawRateValuePubSubType::YawRateValuePubSubType() + { + setName("etsi_its_cam_msgs::msg::dds_::YawRateValue_"); + auto type_size = YawRateValue::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = YawRateValue::isKeyDefined(); + size_t keyLength = YawRateValue::getKeyMaxCdrSerializedSize() > 16 ? + YawRateValue::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + YawRateValuePubSubType::~YawRateValuePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool YawRateValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + YawRateValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool YawRateValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + YawRateValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function YawRateValuePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* YawRateValuePubSubType::createData() + { + return reinterpret_cast(new YawRateValue()); + } + + void YawRateValuePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool YawRateValuePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + YawRateValue* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + YawRateValue::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || YawRateValue::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace etsi_its_cam_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValuePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValuePubSubTypes.h new file mode 100644 index 00000000000..54504cc5def --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValuePubSubTypes.h @@ -0,0 +1,116 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file YawRateValuePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATEVALUE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATEVALUE_PUBSUBTYPES_H_ + +#include +#include + +#include "YawRateValue.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated YawRateValue is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace etsi_its_cam_msgs +{ + namespace msg + { + namespace YawRateValue_Constants + { + + + + + + + } + /*! + * @brief This class represents the TopicDataType of the type YawRateValue defined by the user in the IDL file. + * @ingroup YAWRATEVALUE + */ + class YawRateValuePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef YawRateValue type; + + eProsima_user_DllExport YawRateValuePubSubType(); + + eProsima_user_DllExport virtual ~YawRateValuePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) YawRateValue(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATEVALUE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/fastcdr/Cdr.h b/LibCarla/source/carla/ros2/fastdds/fastcdr/Cdr.h new file mode 100644 index 00000000000..f9e2d9e52f3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/fastcdr/Cdr.h @@ -0,0 +1,3065 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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 _FASTCDR_CDR_H_ +#define _FASTCDR_CDR_H_ + +#include +#include +#include +#include +#include +#include "fastcdr/FastBuffer.h" +#include "fastcdr/exceptions/NotEnoughMemoryException.h" +#include "fastcdr/fastcdr_dll.h" + +#if !__APPLE__ && !__FreeBSD__ && !__VXWORKS__ +#include +#else +#include +#endif // if !__APPLE__ && !__FreeBSD__ && !__VXWORKS__ + +#include + +namespace eprosima { +namespace fastcdr { +/*! + * @brief This class offers an interface to serialize/deserialize some basic types using CDR protocol inside an + * eprosima::fastcdr::FastBuffer. + * @ingroup FASTCDRAPIREFERENCE + */ +class Cdr_DllAPI Cdr { +public: + //! @brief This enumeration represents the two kinds of CDR serialization supported by eprosima::fastcdr::CDR. + typedef enum { + //! @brief Common CORBA CDR serialization. + CORBA_CDR, + //! @brief DDS CDR serialization. + DDS_CDR + } CdrType; + + //! @brief This enumeration represents the two posible values of the flag that points if the content is a parameter + //! list (only in DDS CDR). + + typedef enum : uint8_t { + //! @brief Specifies that the content is not a parameter list. + DDS_CDR_WITHOUT_PL = 0x0, + //! @brief Specifies that the content is a parameter list. + DDS_CDR_WITH_PL = 0x2 + } DDSCdrPlFlag; + + /*! + * @brief This enumeration represents endianness types. + */ + typedef enum : uint8_t { + //! @brief Big endianness. + BIG_ENDIANNESS = 0x0, + //! @brief Little endianness. + LITTLE_ENDIANNESS = 0x1 + } Endianness; + + //! @brief Default endiness in the system. + static const Endianness DEFAULT_ENDIAN; + + /*! + * @brief This class stores the current state of a CDR serialization. + */ + class Cdr_DllAPI state { + friend class Cdr; + + public: + /*! + * @brief Default constructor. + */ + state(const Cdr& cdr); + + /*! + * @brief Copy constructor. + */ + state(const state&); + + private: + state& operator=(const state&) = delete; + + //! @brief The position in the buffer when the state was created. + const FastBuffer::iterator m_currentPosition; + + //! @brief The position from the aligment is calculated, when the state was created.. + const FastBuffer::iterator m_alignPosition; + + //! @brief This attribute specified if it is needed to swap the bytes when the state was created.. + bool m_swapBytes; + + //! @brief Stores the last datasize serialized/deserialized when the state was created. + size_t m_lastDataSize; + }; + + /*! + * @brief This constructor creates an eprosima::fastcdr::Cdr object that can serialize/deserialize + * the assigned buffer. + * + * @param cdrBuffer A reference to the buffer that contains (or will contain) the CDR representation. + * @param endianness The initial endianness that will be used. The default value is the endianness of the system. + * @param cdrType Represents the type of CDR that will be used in serialization/deserialization. The default value is + * CORBA CDR. + */ + Cdr(FastBuffer& cdrBuffer, const Endianness endianness = DEFAULT_ENDIAN, const CdrType cdrType = CORBA_CDR); + + /*! + * @brief This function reads the encapsulation of the CDR stream. + * If the CDR stream contains an encapsulation, then this function should be called before starting to + * deserialize. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + * @exception exception::BadParamException This exception is thrown when trying to deserialize an invalid value. + */ + Cdr& read_encapsulation(); + + /*! + * @brief This function writes the encapsulation of the CDR stream. + * If the CDR stream should contain an encapsulation, then this function should be called before starting to + * serialize. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serialize_encapsulation(); + + /*! + * @brief This function returns the parameter list flag when the CDR type is eprosima::fastcdr::DDS_CDR. + * @return The flag that specifies if the content is a parameter list. + */ + DDSCdrPlFlag getDDSCdrPlFlag() const; + + /*! + * @brief This function sets the parameter list flag when the CDR type is eprosima::fastcdr::DDS_CDR. + * @param plFlag New value for the flag that specifies if the content is a parameter list. + */ + void setDDSCdrPlFlag(DDSCdrPlFlag plFlag); + + /*! + * @brief This function returns the option flags when the CDR type is eprosima::fastcdr::DDS_CDR. + * @return The option flags. + */ + uint16_t getDDSCdrOptions() const; + + /*! + * @brief This function sets the option flags when the CDR type is eprosima::fastcdr::DDS_CDR. + * @param options New value for the option flags. + */ + void setDDSCdrOptions(uint16_t options); + + /*! + * @brief This function sets the current endianness used by the CDR type. + * @param endianness The new endianness value. + */ + void changeEndianness(Endianness endianness); + + /*! + * @brief This function returns the current endianness used by the CDR type. + * @return The endianness. + */ + Endianness endianness() const { + return static_cast(m_endianness); + } + + /*! + * @brief This function skips a number of bytes in the CDR stream buffer. + * @param numBytes The number of bytes that will be jumped. + * @return True is returned when it works successfully. Otherwise, false is returned. + */ + bool jump(size_t numBytes); + + /*! + * @brief This function resets the current position in the buffer to the beginning. + */ + void reset(); + + /*! + * @brief This function returns the pointer to the current used buffer. + * @return Pointer to the starting position of the buffer. + */ + char* getBufferPointer(); + + /*! + * @brief This function returns the current position in the CDR stream. + * @return Pointer to the current position in the buffer. + */ + char* getCurrentPosition(); + + /*! + * @brief This function returns the length of the serialized data inside the stream. + * @return The length of the serialized data. + */ + inline size_t getSerializedDataLength() const { + return m_currentPosition - m_cdrBuffer.begin(); + } + + /*! + * @brief Get the number of bytes needed to align a position to certain data size. + * @param current_alignment Position to be aligned. + * @param dataSize Size of next data to process (should be power of two). + * @return Number of required alignment bytes. + */ + inline static size_t alignment(size_t current_alignment, size_t dataSize) { + return (dataSize - (current_alignment % dataSize)) & (dataSize - 1); + } + + /*! + * @brief This function returns the current state of the CDR serialization process. + * @return The current state of the CDR serialization process. + */ + state getState(); + + /*! + * @brief This function sets a previous state of the CDR serialization process; + * @param state Previous state that will be set. + */ + void setState(state& state); + + /*! + * @brief This function moves the alignment forward. + * @param numBytes The number of bytes the alignment should advance. + * @return True If alignment was moved successfully. + */ + bool moveAlignmentForward(size_t numBytes); + + /*! + * @brief This function resets the alignment to the current position in the buffer. + */ + inline void resetAlignment() { + m_alignPosition = m_currentPosition; + } + + /*! + * @brief This operator serializes an octet. + * @param octet_t The value of the octet that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator<<(const uint8_t octet_t) { + return serialize(octet_t); + } + + /*! + * @brief This operator serializes a character. + * @param char_t The value of the character that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator<<(const char char_t) { + return serialize(char_t); + } + + /*! + * @brief This operator serializes a int8_t. + * @param int8 The value of the int8_t that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator<<(const int8_t int8) { + return serialize(int8); + } + + /*! + * @brief This operator serializes an unsigned short. + * @param ushort_t The value of the unsigned short that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator<<(const uint16_t ushort_t) { + return serialize(ushort_t); + } + + /*! + * @brief This operator serializes a short. + * @param short_t The value of the short that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator<<(const int16_t short_t) { + return serialize(short_t); + } + + /*! + * @brief This operator serializes an unsigned long. + * @param ulong_t The value of the unsigned long that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator<<(const uint32_t ulong_t) { + return serialize(ulong_t); + } + + /*! + * @brief This operator serializes a long. + * @param long_t The value of the long that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator<<(const int32_t long_t) { + return serialize(long_t); + } + + /*! + * @brief This operator serializes a wide-char. + * @param wchar The value of the wide-char that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator<<(const wchar_t wchar) { + return serialize(wchar); + } + + /*! + * @brief This operator serializes an unsigned long long. + * @param ulonglong_t The value of the unsigned long long that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator<<(const uint64_t ulonglong_t) { + return serialize(ulonglong_t); + } + + /*! + * @brief This operator serializes a long long. + * @param longlong_t The value of the long long that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator<<(const int64_t longlong_t) { + return serialize(longlong_t); + } + + /*! + * @brief This operator serializes a float. + * @param float_t The value of the float that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator<<(const float float_t) { + return serialize(float_t); + } + + /*! + * @brief This operator serializes a double. + * @param double_t The value of the double that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator<<(const double double_t) { + return serialize(double_t); + } + + /*! + * @brief This operator serializes a long double. + * @param ldouble_t The value of the long double that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator<<(const long double ldouble_t) { + return serialize(ldouble_t); + } + + /*! + * @brief This operator serializes a boolean. + * @param bool_t The value of the boolean that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator<<(const bool bool_t) { + return serialize(bool_t); + } + + /*! + * @brief This operator serializes a null-terminated c-string. + * @param string_t Pointer to the begining of the string that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator<<(const char* string_t) { + return serialize(string_t); + } + + /*! + * @brief This operator serializes a null-terminated c-string. + * @param string_t Pointer to the begining of the string that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator<<(char* string_t) { + return serialize(string_t); + } + + /*! + * @brief This operator serializes a string. + * @param string_t The string that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator<<(const std::string& string_t) { + return serialize(string_t); + } + + /*! + * @brief This operator serializes a wstring. + * @param string_t The wstring that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator<<(const std::wstring& string_t) { + return serialize(string_t); + } + + /*! + * @brief This operator template is used to serialize arrays. + * @param array_t The array that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + template + inline Cdr& operator<<(const std::array<_T, _Size>& array_t) { + return serialize<_T, _Size>(array_t); + } + + /*! + * @brief This operator template is used to serialize sequences. + * @param vector_t The sequence that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + template + inline Cdr& operator<<(const std::vector<_T, _Alloc>& vector_t) { + return serialize<_T>(vector_t); + } + + /*! + * @brief This operator template is used to serialize maps. + * @param map_t The map that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + template + inline Cdr& operator<<(const std::map<_K, _T>& map_t) { + return serialize<_K, _T>(map_t); + } + + /*! + * @brief This operator template is used to serialize any other non-basic type. + * @param type_t A reference to the object that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + template + inline Cdr& operator<<(const _T& type_t) { + type_t.serialize(*this); + return *this; + } + + /*! + * @brief This operator deserializes an octet. + * @param octet_t The variable that will store the octet read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator>>(uint8_t& octet_t) { + return deserialize(octet_t); + } + + /*! + * @brief This operator deserializes a character. + * @param char_t The variable that will store the character read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator>>(char& char_t) { + return deserialize(char_t); + } + + /*! + * @brief This operator deserializes a int8_t. + * @param int8 The variable that will store the int8_t read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator>>(int8_t& int8) { + return deserialize(int8); + } + + /*! + * @brief This operator deserializes an unsigned short. + * @param ushort_t The variable that will store the unsigned short read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator>>(uint16_t& ushort_t) { + return deserialize(ushort_t); + } + + /*! + * @brief This operator deserializes a short. + * @param short_t The variable that will store the short read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator>>(int16_t& short_t) { + return deserialize(short_t); + } + + /*! + * @brief This operator deserializes an unsigned long. + * @param ulong_t The variable that will store the unsigned long read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator>>(uint32_t& ulong_t) { + return deserialize(ulong_t); + } + + /*! + * @brief This operator deserializes a long. + * @param long_t The variable that will store the long read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator>>(int32_t& long_t) { + return deserialize(long_t); + } + + // TODO in FastCdr + /*! + * @brief This operator deserializes a wide-char. + * @param wchar The variable that will store the wide-char read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator>>(wchar_t& wchar) { + return deserialize(wchar); + } + + /*! + * @brief This operator deserializes a unsigned long long. + * @param ulonglong_t The variable that will store the unsigned long long read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator>>(uint64_t& ulonglong_t) { + return deserialize(ulonglong_t); + } + + /*! + * @brief This operator deserializes a long long. + * @param longlong_t The variable that will store the long long read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator>>(int64_t& longlong_t) { + return deserialize(longlong_t); + } + + /*! + * @brief This operator deserializes a float. + * @param float_t The variable that will store the float read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator>>(float& float_t) { + return deserialize(float_t); + } + + /*! + * @brief This operator deserializes a double. + * @param double_t The variable that will store the double read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator>>(double& double_t) { + return deserialize(double_t); + } + + /*! + * @brief This operator deserializes a long double. + * @param ldouble_t The variable that will store the long double read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator>>(long double& ldouble_t) { + return deserialize(ldouble_t); + } + + /*! + * @brief This operator deserializes a boolean. + * @param bool_t The variable that will store the boolean read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + * @exception exception::BadParamException This exception is thrown when trying to deserialize an invalid value. + */ + inline Cdr& operator>>(bool& bool_t) { + return deserialize(bool_t); + } + + /*! + * @brief This operator deserializes a null-terminated c-string. + * @param string_t The variable that will store the c-string read from the buffer. + * Please note that a newly allocated string will be returned. + * The caller should free the returned pointer when appropiate. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + * @exception exception::BadParamException This exception is thrown when trying to deserialize an invalid value. + */ + inline Cdr& operator>>(char*& string_t) { + return deserialize(string_t); + } + + /*! + * @brief This operator deserializes a string. + * @param string_t The variable that will store the string read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator>>(std::string& string_t) { + return deserialize(string_t); + } + + /*! + * @brief This operator deserializes a string. + * @param string_t The variable that will store the string read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& operator>>(std::wstring& string_t) { + return deserialize(string_t); + } + + /*! + * @brief This operator template is used to deserialize arrays. + * @param array_t The variable that will store the array read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template + inline Cdr& operator>>(std::array<_T, _Size>& array_t) { + return deserialize<_T, _Size>(array_t); + } + + /*! + * @brief This operator template is used to deserialize sequences. + * @param vector_t The variable that will store the sequence read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template + inline Cdr& operator>>(std::vector<_T, _Alloc>& vector_t) { + return deserialize<_T>(vector_t); + } + + /*! + * @brief This operator template is used to deserialize maps. + * @param map_t The variable that will store the map read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template + inline Cdr& operator>>(std::map<_K, _T>& map_t) { + return deserialize<_K, _T>(map_t); + } + + /*! + * @brief This operator template is used to deserialize any other non-basic type. + * @param type_t The variable that will store the object read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + template + inline Cdr& operator>>(_T& type_t) { + type_t.deserialize(*this); + return *this; + } + + /*! + * @brief This function serializes an octet. + * @param octet_t The value of the octet that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serialize(const uint8_t octet_t) { + return serialize(static_cast(octet_t)); + } + + /*! + * @brief This function serializes an octet with a different endianness. + * @param octet_t The value of the octet that will be serialized in the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serialize(const uint8_t octet_t, Endianness endianness) { + return serialize(static_cast(octet_t), endianness); + } + + /*! + * @brief This function serializes a character. + * @param char_t The value of the character that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serialize(const char char_t); + + /*! + * @brief This function serializes a character with a different endianness. + * @param char_t The value of the character that will be serialized in the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serialize(const char char_t, Endianness endianness) { + (void)endianness; + return serialize(char_t); + } + + /*! + * @brief This function serializes an int8_t. + * @param int8 The value of the int8_t that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serialize(const int8_t int8) { + return serialize(static_cast(int8)); + } + + /*! + * @brief This function serializes an int8_t with a different endianness. + * @param int8 The value of the int8_t that will be serialized in the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serialize(const int8_t int8, Endianness endianness) { + return serialize(static_cast(int8), endianness); + } + + /*! + * @brief This function serializes an unsigned short. + * @param ushort_t The value of the unsigned short that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serialize(const uint16_t ushort_t) { + return serialize(static_cast(ushort_t)); + } + + /*! + * @brief This function serializes an unsigned short with a different endianness. + * @param ushort_t The value of the unsigned short that will be serialized in the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serialize(const uint16_t ushort_t, Endianness endianness) { + return serialize(static_cast(ushort_t), endianness); + } + + /*! + * @brief This function serializes a short. + * @param short_t The value of the short that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serialize(const int16_t short_t); + + /*! + * @brief This function serializes a short with a different endianness. + * @param short_t The value of the short that will be serialized in the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serialize(const int16_t short_t, Endianness endianness); + + /*! + * @brief This function serializes an unsigned long. + * @param ulong_t The value of the unsigned long that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serialize(const uint32_t ulong_t) { + return serialize(static_cast(ulong_t)); + } + + /*! + * @brief This function serializes an unsigned long with a different endianness. + * @param ulong_t The value of the unsigned long that will be serialized in the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serialize(const uint32_t ulong_t, Endianness endianness) { + return serialize(static_cast(ulong_t), endianness); + } + + /*! + * @brief This function serializes a long. + * @param long_t The value of the long that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serialize(const int32_t long_t); + + /*! + * @brief This function serializes a long with a different endianness. + * @param long_t The value of the long that will be serialized in the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serialize(const int32_t long_t, Endianness endianness); + + /*! + * @brief This function serializes a wide-char. + * @param wchar The value of the wide-char that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serialize(const wchar_t wchar) { + return serialize(static_cast(wchar)); + } + + /*! + * @brief This function serializes a wide-char with a different endianness. + * @param wchar The value of the wide-char that will be serialized in the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serialize(const wchar_t wchar, Endianness endianness) { + return serialize(static_cast(wchar), endianness); + } + + /*! + * @brief This function serializes an unsigned long long. + * @param ulonglong_t The value of the unsigned long long that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serialize(const uint64_t ulonglong_t) { + return serialize(static_cast(ulonglong_t)); + } + + /*! + * @brief This function serializes an unsigned long long with a different endianness. + * @param ulonglong_t The value of the unsigned long long that will be serialized in the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serialize(const uint64_t ulonglong_t, Endianness endianness) { + return serialize(static_cast(ulonglong_t), endianness); + } + + /*! + * @brief This function serializes a long long. + * @param longlong_t The value of the long long that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serialize(const int64_t longlong_t); + + /*! + * @brief This function serializes a long long with a different endianness. + * @param longlong_t The value of the long long that will be serialized in the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serialize(const int64_t longlong_t, Endianness endianness); + + /*! + * @brief This function serializes a float. + * @param float_t The value of the float that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serialize(const float float_t); + + /*! + * @brief This function serializes a float with a different endianness. + * @param float_t The value of the float that will be serialized in the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serialize(const float float_t, Endianness endianness); + + /*! + * @brief This function serializes a double. + * @param double_t The value of the double that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serialize(const double double_t); + + /*! + * @brief This function serializes a double with a different endianness. + * @param double_t The value of the double that will be serialized in the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serialize(const double double_t, Endianness endianness); + + /*! + * @brief This function serializes a long double. + * @param ldouble_t The value of the long double that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + * @note Due to internal representation differences, WIN32 and *NIX like systems are not compatible. + */ + Cdr& serialize(const long double ldouble_t); + + /*! + * @brief This function serializes a long double with a different endianness. + * @param ldouble_t The value of the long double that will be serialized in the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + * @note Due to internal representation differences, WIN32 and *NIX like systems are not compatible. + */ + Cdr& serialize(const long double ldouble_t, Endianness endianness); + + /*! + * @brief This function serializes a boolean. + * @param bool_t The value of the boolean that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serialize(const bool bool_t); + + /*! + * @brief This function serializes a boolean with a different endianness. + * @param bool_t The value of the boolean that will be serialized in the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serialize(const bool bool_t, Endianness endianness) { + (void)endianness; + return serialize(bool_t); + } + + /*! + * @brief This function serializes a string. + * @param string_t The pointer to the string that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serialize(char* string_t) { + return serialize(static_cast(string_t)); + } + + /*! + * @brief This function serializes a string. + * @param string_t The pointer to the string that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serialize(const char* string_t); + + /*! + * @brief This function serializes a wstring. + * @param string_t The pointer to the wstring that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serialize(const wchar_t* string_t); + + /*! + * @brief This function serializes a string with a different endianness. + * @param string_t The pointer to the string that will be serialized in the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serialize(const char* string_t, Endianness endianness); + + /*! + * @brief This function serializes a wstring with a different endianness. + * @param string_t The pointer to the wstring that will be serialized in the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serialize(const wchar_t* string_t, Endianness endianness); + + /*! + * @brief This function serializes a std::string. + * @param string_t The string that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serialize(const std::string& string_t) { + return serialize(string_t.c_str()); + } + + /*! + * @brief This function serializes a std::wstring. + * @param string_t The wstring that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serialize(const std::wstring& string_t) { + return serialize(string_t.c_str()); + } + + /*! + * @brief This function serializes a std::string with a different endianness. + * @param string_t The string that will be serialized in the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serialize(const std::string& string_t, Endianness endianness) { + return serialize(string_t.c_str(), endianness); + } + + /*! + * @brief This function template serializes an array. + * @param array_t The array that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + template + inline Cdr& serialize(const std::array<_T, _Size>& array_t) { + return serializeArray(array_t.data(), array_t.size()); + } + + /*! + * @brief This function template serializes an array with a different endianness. + * @param array_t The array that will be serialized in the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + template + inline Cdr& serialize(const std::array<_T, _Size>& array_t, Endianness endianness) { + return serializeArray(array_t.data(), array_t.size(), endianness); + } + + /*! + * @brief This function template serializes a sequence of booleans. + * @param vector_t The sequence that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + template + Cdr& serialize(const std::vector& vector_t) { + return serializeBoolSequence(vector_t); + } + + /*! + * @brief This function template serializes a sequence. + * @param vector_t The sequence that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + template + Cdr& serialize(const std::vector<_T, _Alloc>& vector_t) { + state state_before_error(*this); + + *this << static_cast(vector_t.size()); + + try { + return serializeArray(vector_t.data(), vector_t.size()); + } catch (eprosima::fastcdr::exception::Exception& ex) { + setState(state_before_error); + ex.raise(); + } + + return *this; + } + + /*! + * @brief This function template serializes a map. + * @param map_t The map that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + template + Cdr& serialize(const std::map<_K, _T>& map_t) { + state state_(*this); + + *this << static_cast(map_t.size()); + + try { + for (auto it_pair = map_t.begin(); it_pair != map_t.end(); ++it_pair) { + *this << it_pair->first; + *this << it_pair->second; + } + // return serializeArray(map_t.data(), map_t.size()); + } catch (eprosima::fastcdr::exception::Exception& ex) { + setState(state_); + ex.raise(); + } + + return *this; + } + +#ifdef _MSC_VER + /*! + * @brief This function template serializes a sequence of booleans. + * @param vector_t The sequence that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + template <> + Cdr& serialize(const std::vector& vector_t) { + return serializeBoolSequence(vector_t); + } + +#endif // ifdef _MSC_VER + + /*! + * @brief This function template serializes a sequence with a different endianness. + * @param vector_t The sequence that will be serialized in the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + template + Cdr& serialize(const std::vector<_T, _Alloc>& vector_t, Endianness endianness) { + bool auxSwap = m_swapBytes; + m_swapBytes = (m_swapBytes && (static_cast(m_endianness) == endianness)) || + (!m_swapBytes && (static_cast(m_endianness) != endianness)); + + try { + serialize(vector_t); + m_swapBytes = auxSwap; + } catch (eprosima::fastcdr::exception::Exception& ex) { + m_swapBytes = auxSwap; + ex.raise(); + } + + return *this; + } + + /*! + * @brief This function template serializes a non-basic object. + * @param type_t The object that will be serialized in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + template + inline Cdr& serialize(const _T& type_t) { + type_t.serialize(*this); + return *this; + } + + /*! + * @brief This function serializes an array of octets. + * @param octet_t The sequence of octets that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serializeArray(const uint8_t* octet_t, size_t numElements) { + return serializeArray(reinterpret_cast(octet_t), numElements); + } + + /*! + * @brief This function serializes an array of octets with a different endianness. + * @param octet_t The array of octets that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serializeArray(const uint8_t* octet_t, size_t numElements, Endianness endianness) { + (void)endianness; + return serializeArray(reinterpret_cast(octet_t), numElements); + } + + /*! + * @brief This function serializes an array of characters. + * @param char_t The array of characters that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serializeArray(const char* char_t, size_t numElements); + + /*! + * @brief This function serializes an array of characters with a different endianness. + * @param char_t The array of characters that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serializeArray(const char* char_t, size_t numElements, Endianness endianness) { + (void)endianness; + return serializeArray(char_t, numElements); + } + + /*! + * @brief This function serializes an array of int8_t. + * @param int8 The sequence of int8_t that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serializeArray(const int8_t* int8, size_t numElements) { + return serializeArray(reinterpret_cast(int8), numElements); + } + + /*! + * @brief This function serializes an array of int8_t with a different endianness. + * @param int8 The array of int8_t that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serializeArray(const int8_t* int8, size_t numElements, Endianness endianness) { + (void)endianness; + return serializeArray(reinterpret_cast(int8), numElements); + } + + /*! + * @brief This function serializes an array of unsigned shorts. + * @param ushort_t The array of unsigned shorts that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serializeArray(const uint16_t* ushort_t, size_t numElements) { + return serializeArray(reinterpret_cast(ushort_t), numElements); + } + + /*! + * @brief This function serializes an array of unsigned shorts with a different endianness. + * @param ushort_t The array of unsigned shorts that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serializeArray(const uint16_t* ushort_t, size_t numElements, Endianness endianness) { + return serializeArray(reinterpret_cast(ushort_t), numElements, endianness); + } + + /*! + * @brief This function serializes an array of shorts. + * @param short_t The array of shorts that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serializeArray(const int16_t* short_t, size_t numElements); + + /*! + * @brief This function serializes an array of shorts with a different endianness. + * @param short_t The array of shorts that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serializeArray(const int16_t* short_t, size_t numElements, Endianness endianness); + + /*! + * @brief This function serializes an array of unsigned longs. + * @param ulong_t The array of unsigned longs that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serializeArray(const uint32_t* ulong_t, size_t numElements) { + return serializeArray(reinterpret_cast(ulong_t), numElements); + } + + /*! + * @brief This function serializes an array of unsigned longs with a different endianness. + * @param ulong_t The array of unsigned longs that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serializeArray(const uint32_t* ulong_t, size_t numElements, Endianness endianness) { + return serializeArray(reinterpret_cast(ulong_t), numElements, endianness); + } + + /*! + * @brief This function serializes an array of longs. + * @param long_t The array of longs that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serializeArray(const int32_t* long_t, size_t numElements); + + /*! + * @brief This function serializes an array of longs with a different endianness. + * @param long_t The array of longs that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serializeArray(const int32_t* long_t, size_t numElements, Endianness endianness); + + /*! + * @brief This function serializes an array of wide-chars. + * @param wchar The array of wide-chars that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serializeArray(const wchar_t* wchar, size_t numElements); + + /*! + * @brief This function serializes an array of wide-chars with a different endianness. + * @param wchar The array of longs that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serializeArray(const wchar_t* wchar, size_t numElements, Endianness endianness); + + /*! + * @brief This function serializes an array of unsigned long longs. + * @param ulonglong_t The array of unsigned long longs that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serializeArray(const uint64_t* ulonglong_t, size_t numElements) { + return serializeArray(reinterpret_cast(ulonglong_t), numElements); + } + + /*! + * @brief This function serializes an array of unsigned long longs with a different endianness. + * @param ulonglong_t The array of unsigned long longs that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serializeArray(const uint64_t* ulonglong_t, size_t numElements, Endianness endianness) { + return serializeArray(reinterpret_cast(ulonglong_t), numElements, endianness); + } + + /*! + * @brief This function serializes an array of long longs. + * @param longlong_t The array of long longs that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serializeArray(const int64_t* longlong_t, size_t numElements); + + /*! + * @brief This function serializes an array of long longs with a different endianness. + * @param longlong_t The array of long longs that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serializeArray(const int64_t* longlong_t, size_t numElements, Endianness endianness); + + /*! + * @brief This function serializes an array of floats. + * @param float_t The array of floats that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serializeArray(const float* float_t, size_t numElements); + + /*! + * @brief This function serializes an array of floats with a different endianness. + * @param float_t The array of floats that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serializeArray(const float* float_t, size_t numElements, Endianness endianness); + + /*! + * @brief This function serializes an array of doubles. + * @param double_t The array of doubles that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serializeArray(const double* double_t, size_t numElements); + + /*! + * @brief This function serializes an array of doubles with a different endianness. + * @param double_t The array of doubles that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serializeArray(const double* double_t, size_t numElements, Endianness endianness); + + /*! + * @brief This function serializes an array of long doubles. + * @param ldouble_t The array of long doubles that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serializeArray(const long double* ldouble_t, size_t numElements); + + /*! + * @brief This function serializes an array of long doubles with a different endianness. + * @param ldouble_t The array of long doubles that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serializeArray(const long double* ldouble_t, size_t numElements, Endianness endianness); + + /*! + * @brief This function serializes an array of booleans. + * @param bool_t The array of booleans that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + Cdr& serializeArray(const bool* bool_t, size_t numElements); + + /*! + * @brief This function serializes an array of booleans with a different endianness. + * @param bool_t The array of booleans that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serializeArray(const bool* bool_t, size_t numElements, Endianness endianness) { + (void)endianness; + return serializeArray(bool_t, numElements); + } + + /*! + * @brief This function serializes an array of strings. + * @param string_t The array of strings that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serializeArray(const std::string* string_t, size_t numElements) { + for (size_t count = 0; count < numElements; ++count) { + serialize(string_t[count].c_str()); + } + return *this; + } + + /*! + * @brief This function serializes an array of wide-strings. + * @param string_t The array of wide-strings that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serializeArray(const std::wstring* string_t, size_t numElements) { + for (size_t count = 0; count < numElements; ++count) { + serialize(string_t[count].c_str()); + } + return *this; + } + + /*! + * @brief This function serializes an array of strings with a different endianness. + * @param string_t The array of strings that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serializeArray(const std::string* string_t, size_t numElements, Endianness endianness) { + bool auxSwap = m_swapBytes; + m_swapBytes = (m_swapBytes && (static_cast(m_endianness) == endianness)) || + (!m_swapBytes && (static_cast(m_endianness) != endianness)); + + try { + serializeArray(string_t, numElements); + m_swapBytes = auxSwap; + } catch (eprosima::fastcdr::exception::Exception& ex) { + m_swapBytes = auxSwap; + ex.raise(); + } + + return *this; + } + + /*! + * @brief This function serializes an array of wide-strings with a different endianness. + * @param string_t The array of wide-strings that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + inline Cdr& serializeArray(const std::wstring* string_t, size_t numElements, Endianness endianness) { + bool auxSwap = m_swapBytes; + m_swapBytes = (m_swapBytes && (static_cast(m_endianness) == endianness)) || + (!m_swapBytes && (static_cast(m_endianness) != endianness)); + + try { + serializeArray(string_t, numElements); + m_swapBytes = auxSwap; + } catch (eprosima::fastcdr::exception::Exception& ex) { + m_swapBytes = auxSwap; + ex.raise(); + } + + return *this; + } + + /*! + * @brief This function template serializes an array of sequences of objects. + * @param vector_t The array of sequences of objects that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + template + Cdr& serializeArray(const std::vector<_T, _Alloc>* vector_t, size_t numElements) { + for (size_t count = 0; count < numElements; ++count) { + serialize(vector_t[count]); + } + return *this; + } + + /*! + * @brief This function template serializes an array of non-basic objects. + * @param type_t The array of objects that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + template + Cdr& serializeArray(const _T* type_t, size_t numElements) { + for (size_t count = 0; count < numElements; ++count) { + type_t[count].serialize(*this); + } + return *this; + } + + /*! + * @brief This function template serializes an array of non-basic objects with a different endianness. + * @param type_t The array of objects that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + template + Cdr& serializeArray(const _T* type_t, size_t numElements, Endianness endianness) { + bool auxSwap = m_swapBytes; + m_swapBytes = (m_swapBytes && (static_cast(m_endianness) == endianness)) || + (!m_swapBytes && (static_cast(m_endianness) != endianness)); + + try { + serializeArray(type_t, numElements); + m_swapBytes = auxSwap; + } catch (eprosima::fastcdr::exception::Exception& ex) { + m_swapBytes = auxSwap; + ex.raise(); + } + + return *this; + } + + /*! + * @brief This function template serializes a raw sequence. + * @param sequence_t Pointer to the sequence that will be serialized in the buffer. + * @param numElements The number of elements contained in the sequence. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + template + Cdr& serializeSequence(const _T* sequence_t, size_t numElements) { + state state_before_error(*this); + + serialize(static_cast(numElements)); + + try { + return serializeArray(sequence_t, numElements); + } catch (eprosima::fastcdr::exception::Exception& ex) { + setState(state_before_error); + ex.raise(); + } + + return *this; + } + + /*! + * @brief This function template serializes a raw sequence with a different endianness. + * @param sequence_t Pointer to the sequence that will be serialized in the buffer. + * @param numElements The number of elements contained in the sequence. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + template + Cdr& serializeSequence(const _T* sequence_t, size_t numElements, Endianness endianness) { + bool auxSwap = m_swapBytes; + m_swapBytes = (m_swapBytes && (static_cast(m_endianness) == endianness)) || + (!m_swapBytes && (static_cast(m_endianness) != endianness)); + + try { + serializeSequence(sequence_t, numElements); + m_swapBytes = auxSwap; + } catch (eprosima::fastcdr::exception::Exception& ex) { + m_swapBytes = auxSwap; + ex.raise(); + } + + return *this; + } + + /*! + * @brief This function deserializes an octet. + * @param octet_t The variable that will store the octet read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserialize(uint8_t& octet_t) { + return deserialize(reinterpret_cast(octet_t)); + } + + /*! + * @brief This function deserializes an octet with a different endianness. + * @param octet_t The variable that will store the octet read from the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserialize(uint8_t& octet_t, Endianness endianness) { + return deserialize(reinterpret_cast(octet_t), endianness); + } + + /*! + * @brief This function deserializes a character. + * @param char_t The variable that will store the character read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserialize(char& char_t); + + /*! + * @brief This function deserializes a character with a different endianness. + * @param char_t The variable that will store the character read from the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserialize(char& char_t, Endianness endianness) { + (void)endianness; + return deserialize(char_t); + } + + /*! + * @brief This function deserializes an int8_t. + * @param int8 The variable that will store the int8_t read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserialize(int8_t& int8) { + return deserialize(reinterpret_cast(int8)); + } + + /*! + * @brief This function deserializes an int8_t with a different endianness. + * @param int8 The variable that will store the int8_t read from the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserialize(int8_t& int8, Endianness endianness) { + return deserialize(reinterpret_cast(int8), endianness); + } + + /*! + * @brief This function deserializes an unsigned short. + * @param ushort_t The variable that will store the unsigned short read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserialize(uint16_t& ushort_t) { + return deserialize(reinterpret_cast(ushort_t)); + } + + /*! + * @brief This function deserializes an unsigned short with a different endianness. + * @param ushort_t The variable that will store the unsigned short read from the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserialize(uint16_t& ushort_t, Endianness endianness) { + return deserialize(reinterpret_cast(ushort_t), endianness); + } + + /*! + * @brief This function deserializes a short. + * @param short_t The variable that will store the short read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserialize(int16_t& short_t); + + /*! + * @brief This function deserializes a short with a different endianness. + * @param short_t The variable that will store the short read from the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserialize(int16_t& short_t, Endianness endianness); + + /*! + * @brief This function deserializes an unsigned long. + * @param ulong_t The variable that will store the unsigned long read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserialize(uint32_t& ulong_t) { + return deserialize(reinterpret_cast(ulong_t)); + } + + /*! + * @brief This function deserializes an unsigned long with a different endianness. + * @param ulong_t The variable that will store the unsigned long read from the buffer.. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserialize(uint32_t& ulong_t, Endianness endianness) { + return deserialize(reinterpret_cast(ulong_t), endianness); + } + + /*! + * @brief This function deserializes a long. + * @param long_t The variable that will store the long read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserialize(int32_t& long_t); + + /*! + * @brief This function deserializes a long with a different endianness. + * @param long_t The variable that will store the long read from the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserialize(int32_t& long_t, Endianness endianness); + + /*! + * @brief This function deserializes a wide-char. + * @param wchar The variable that will store the wide-char read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserialize(wchar_t& wchar) { + uint32_t ret; + deserialize(ret); + wchar = static_cast(ret); + return *this; + } + + /*! + * @brief This function deserializes a wide-char with a different endianness. + * @param wchar The variable that will store the wide-char read from the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserialize(wchar_t& wchar, Endianness endianness) { + uint32_t ret; + deserialize(ret, endianness); + wchar = static_cast(ret); + return *this; + } + + /*! + * @brief This function deserializes an unsigned long long. + * @param ulonglong_t The variable that will store the unsigned long long read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserialize(uint64_t& ulonglong_t) { + return deserialize(reinterpret_cast(ulonglong_t)); + } + + /*! + * @brief This function deserializes an unsigned long long with a different endianness. + * @param ulonglong_t The variable that will store the unsigned long long read from the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserialize(uint64_t& ulonglong_t, Endianness endianness) { + return deserialize(reinterpret_cast(ulonglong_t), endianness); + } + + /*! + * @brief This function deserializes a long long. + * @param longlong_t The variable that will store the long long read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserialize(int64_t& longlong_t); + + /*! + * @brief This function deserializes a long long with a different endianness. + * @param longlong_t The variable that will store the long long read from the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserialize(int64_t& longlong_t, Endianness endianness); + + /*! + * @brief This function deserializes a float. + * @param float_t The variable that will store the float read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserialize(float& float_t); + + /*! + * @brief This function deserializes a float with a different endianness. + * @param float_t The variable that will store the float read from the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserialize(float& float_t, Endianness endianness); + + /*! + * @brief This function deserializes a double. + * @param double_t The variable that will store the double read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserialize(double& double_t); + + /*! + * @brief This function deserializes a double with a different endianness. + * @param double_t The variable that will store the double read from the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserialize(double& double_t, Endianness endianness); + + /*! + * @brief This function deserializes a long double. + * @param ldouble_t The variable that will store the long double read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + * @note Due to internal representation differences, WIN32 and *NIX like systems are not compatible. + */ + Cdr& deserialize(long double& ldouble_t); + + /*! + * @brief This function deserializes a long double with a different endianness. + * @param ldouble_t The variable that will store the long double read from the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + * @note Due to internal representation differences, WIN32 and *NIX like systems are not compatible. + */ + Cdr& deserialize(long double& ldouble_t, Endianness endianness); + + /*! + * @brief This function deserializes a boolean. + * @param bool_t The variable that will store the boolean read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + * @exception exception::BadParamException This exception is thrown when trying to deserialize an invalid value. + */ + Cdr& deserialize(bool& bool_t); + + /*! + * @brief This function deserializes a boolean with a different endianness. + * @param bool_t The variable that will store the boolean read from the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + * @exception exception::BadParamException This exception is thrown when trying to deserialize an invalid value. + */ + inline Cdr& deserialize(bool& bool_t, Endianness endianness) { + (void)endianness; + return deserialize(bool_t); + } + + /*! + * @brief This function deserializes a string. + * This function allocates memory to store the string. The user pointer will be set to point this allocated memory. + * The user will have to free this allocated memory using free() + * @param string_t The pointer that will point to the string read from the buffer. + * The user will have to free the allocated memory using free() + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserialize(char*& string_t); + + /*! + * @brief This function deserializes a wide string. + * This function allocates memory to store the wide string. The user pointer will be set to point this allocated + * memory. The user will have to free this allocated memory using free() + * @param string_t The pointer that will point to the wide string read from the buffer. + * The user will have to free the allocated memory using free() + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserialize(wchar_t*& string_t); + + /*! + * @brief This function deserializes a string with a different endianness. + * This function allocates memory to store the string. The user pointer will be set to point this allocated memory. + * The user will have to free this allocated memory using free() + * @param string_t The pointer that will point to the string read from the buffer. + * @param endianness Endianness that will be used in the deserialization of this value. + * The user will have to free the allocated memory using free() + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserialize(char*& string_t, Endianness endianness); + + /*! + * @brief This function deserializes a wide string with a different endianness. + * This function allocates memory to store the wide string. The user pointer will be set to point this allocated + * memory. The user will have to free this allocated memory using free() + * @param string_t The pointer that will point to the wide string read from the buffer. + * @param endianness Endianness that will be used in the deserialization of this value. + * The user will have to free the allocated memory using free() + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserialize(wchar_t*& string_t, Endianness endianness); + + /*! + * @brief This function deserializes a std::string. + * @param string_t The variable that will store the string read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserialize(std::string& string_t) { + uint32_t length = 0; + const char* str = readString(length); + string_t.assign(str, length); + return *this; + } + + /*! + * @brief This function deserializes a std::string. + * @param string_t The variable that will store the string read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserialize(std::wstring& string_t) { + uint32_t length = 0; + string_t = readWString(length); + return *this; + } + + /*! + * @brief This function deserializes a string with a different endianness. + * @param string_t The variable that will store the string read from the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserialize(std::string& string_t, Endianness endianness) { + bool auxSwap = m_swapBytes; + m_swapBytes = (m_swapBytes && (static_cast(m_endianness) == endianness)) || + (!m_swapBytes && (static_cast(m_endianness) != endianness)); + + try { + deserialize(string_t); + m_swapBytes = auxSwap; + } catch (eprosima::fastcdr::exception::Exception& ex) { + m_swapBytes = auxSwap; + ex.raise(); + } + + return *this; + } + + /*! + * @brief This function deserializes a string with a different endianness. + * @param string_t The variable that will store the string read from the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserialize(std::wstring& string_t, Endianness endianness) { + bool auxSwap = m_swapBytes; + m_swapBytes = (m_swapBytes && (static_cast(m_endianness) == endianness)) || + (!m_swapBytes && (static_cast(m_endianness) != endianness)); + + try { + deserialize(string_t); + m_swapBytes = auxSwap; + } catch (eprosima::fastcdr::exception::Exception& ex) { + m_swapBytes = auxSwap; + ex.raise(); + } + + return *this; + } + + /*! + * @brief This function template deserializes an array. + * @param array_t The variable that will store the array read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template + inline Cdr& deserialize(std::array<_T, _Size>& array_t) { + return deserializeArray(array_t.data(), array_t.size()); + } + + /*! + * @brief This function template deserializes an array with a different endianness. + * @param array_t The variable that will store the array read from the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template + inline Cdr& deserialize(std::array<_T, _Size>& array_t, Endianness endianness) { + return deserializeArray(array_t.data(), array_t.size(), endianness); + } + + /*! + * @brief This function template deserializes a sequence. + * @param vector_t The variable that will store the sequence read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template + Cdr& deserialize(std::vector& vector_t) { + return deserializeBoolSequence(vector_t); + } + + /*! + * @brief This function template deserializes a sequence. + * @param vector_t The variable that will store the sequence read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template + Cdr& deserialize(std::vector<_T, _Alloc>& vector_t) { + uint32_t seqLength = 0; + state state_before_error(*this); + + *this >> seqLength; + + if (seqLength == 0) { + vector_t.clear(); + return *this; + } + + if ((m_lastPosition - m_currentPosition) < seqLength) { + setState(state_before_error); + throw eprosima::fastcdr::exception::NotEnoughMemoryException( + eprosima::fastcdr::exception::NotEnoughMemoryException::NOT_ENOUGH_MEMORY_MESSAGE_DEFAULT); + } + + try { + vector_t.resize(seqLength); + return deserializeArray(vector_t.data(), vector_t.size()); + } catch (eprosima::fastcdr::exception::Exception& ex) { + setState(state_before_error); + ex.raise(); + } + + return *this; + } + + /*! + * @brief This function template deserializes a map. + * @param map_t The variable that will store the map read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template + Cdr& deserialize(std::map<_K, _T>& map_t) { + uint32_t seqLength = 0; + state state_(*this); + + *this >> seqLength; + + try { + for (uint32_t i = 0; i < seqLength; ++i) { + _K key; + _T value; + *this >> key; + *this >> value; + map_t.emplace(std::pair<_K, _T>(std::move(key), std::move(value))); + } + } catch (eprosima::fastcdr::exception::Exception& ex) { + setState(state_); + ex.raise(); + } + + return *this; + } + +#ifdef _MSC_VER + /*! + * @brief This function template deserializes a sequence. + * @param vector_t The variable that will store the sequence read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template <> + Cdr& deserialize(std::vector& vector_t) { + return deserializeBoolSequence(vector_t); + } + +#endif // ifdef _MSC_VER + + /*! + * @brief This function template deserializes a sequence with a different endianness. + * @param vector_t The variable that will store the sequence read from the buffer. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template + Cdr& deserialize(std::vector<_T, _Alloc>& vector_t, Endianness endianness) { + bool auxSwap = m_swapBytes; + m_swapBytes = (m_swapBytes && (static_cast(m_endianness) == endianness)) || + (!m_swapBytes && (static_cast(m_endianness) != endianness)); + + try { + deserialize(vector_t); + m_swapBytes = auxSwap; + } catch (exception::Exception& ex) { + m_swapBytes = auxSwap; + ex.raise(); + } + + return *this; + } + + /*! + * @brief This function template deserializes a non-basic object. + * @param type_t The variable that will store the object read from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template + inline Cdr& deserialize(_T& type_t) { + type_t.deserialize(*this); + return *this; + } + + /*! + * @brief This function deserializes an array of octets. + * @param octet_t The variable that will store the array of octets read from the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserializeArray(uint8_t* octet_t, size_t numElements) { + return deserializeArray(reinterpret_cast(octet_t), numElements); + } + + /*! + * @brief This function deserializes an array of octets with a different endianness. + * @param octet_t The variable that will store the array of octets read from the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserializeArray(uint8_t* octet_t, size_t numElements, Endianness endianness) { + return deserializeArray(reinterpret_cast(octet_t), numElements, endianness); + } + + /*! + * @brief This function deserializes an array of characters. + * @param char_t The variable that will store the array of characters read from the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserializeArray(char* char_t, size_t numElements); + + /*! + * @brief This function deserializes an array of characters with a different endianness. + * @param char_t The variable that will store the array of characters read from the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserializeArray(char* char_t, size_t numElements, Endianness endianness) { + (void)endianness; + return deserializeArray(char_t, numElements); + } + + /*! + * @brief This function deserializes an array of int8_t. + * @param int8 The variable that will store the array of int8_t read from the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserializeArray(int8_t* int8, size_t numElements) { + return deserializeArray(reinterpret_cast(int8), numElements); + } + + /*! + * @brief This function deserializes an array of int8_t with a different endianness. + * @param int8 The variable that will store the array of int8_t read from the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserializeArray(int8_t* int8, size_t numElements, Endianness endianness) { + return deserializeArray(reinterpret_cast(int8), numElements, endianness); + } + + /*! + * @brief This function deserializes an array of unsigned shorts. + * @param ushort_t The variable that will store the array of unsigned shorts read from the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserializeArray(uint16_t* ushort_t, size_t numElements) { + return deserializeArray(reinterpret_cast(ushort_t), numElements); + } + + /*! + * @brief This function deserializes an array of unsigned shorts with a different endianness. + * @param ushort_t The variable that will store the array of unsigned shorts read from the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserializeArray(uint16_t* ushort_t, size_t numElements, Endianness endianness) { + return deserializeArray(reinterpret_cast(ushort_t), numElements, endianness); + } + + /*! + * @brief This function deserializes an array of shorts. + * @param short_t The variable that will store the array of shorts read from the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserializeArray(int16_t* short_t, size_t numElements); + + /*! + * @brief This function deserializes an array of shorts with a different endianness. + * @param short_t The variable that will store the array of shorts read from the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserializeArray(int16_t* short_t, size_t numElements, Endianness endianness); + + /*! + * @brief This function deserializes an array of unsigned longs. + * @param ulong_t The variable that will store the array of unsigned longs read from the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserializeArray(uint32_t* ulong_t, size_t numElements) { + return deserializeArray(reinterpret_cast(ulong_t), numElements); + } + + /*! + * @brief This function deserializes an array of unsigned longs with a different endianness. + * @param ulong_t The variable that will store the array of unsigned longs read from the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserializeArray(uint32_t* ulong_t, size_t numElements, Endianness endianness) { + return deserializeArray(reinterpret_cast(ulong_t), numElements, endianness); + } + + /*! + * @brief This function deserializes an array of longs. + * @param long_t The variable that will store the array of longs read from the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserializeArray(int32_t* long_t, size_t numElements); + + /*! + * @brief This function deserializes an array of longs with a different endianness. + * @param long_t The variable that will store the array of longs read from the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserializeArray(int32_t* long_t, size_t numElements, Endianness endianness); + + /*! + * @brief This function deserializes an array of wide-chars. + * @param wchar The variable that will store the array of wide-chars read from the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserializeArray(wchar_t* wchar, size_t numElements); + + /*! + * @brief This function deserializes an array of wide-chars with a different endianness. + * @param wchar The variable that will store the array of wide-chars read from the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserializeArray(wchar_t* wchar, size_t numElements, Endianness endianness); + + /*! + * @brief This function deserializes an array of unsigned long longs. + * @param ulonglong_t The variable that will store the array of unsigned long longs read from the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserializeArray(uint64_t* ulonglong_t, size_t numElements) { + return deserializeArray(reinterpret_cast(ulonglong_t), numElements); + } + + /*! + * @brief This function deserializes an array of unsigned long longs with a different endianness. + * @param ulonglong_t The variable that will store the array of unsigned long longs read from the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserializeArray(uint64_t* ulonglong_t, size_t numElements, Endianness endianness) { + return deserializeArray(reinterpret_cast(ulonglong_t), numElements, endianness); + } + + /*! + * @brief This function deserializes an array of long longs. + * @param longlong_t The variable that will store the array of long longs read from the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserializeArray(int64_t* longlong_t, size_t numElements); + + /*! + * @brief This function deserializes an array of long longs with a different endianness. + * @param longlong_t The variable that will store the array of long longs read from the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserializeArray(int64_t* longlong_t, size_t numElements, Endianness endianness); + + /*! + * @brief This function deserializes an array of floats. + * @param float_t The variable that will store the array of floats read from the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserializeArray(float* float_t, size_t numElements); + + /*! + * @brief This function deserializes an array of floats with a different endianness. + * @param float_t The variable that will store the array of floats read from the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserializeArray(float* float_t, size_t numElements, Endianness endianness); + + /*! + * @brief This function deserializes an array of doubles. + * @param double_t The variable that will store the array of doubles read from the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserializeArray(double* double_t, size_t numElements); + + /*! + * @brief This function deserializes an array of doubles with a different endianness. + * @param double_t The variable that will store the array of doubles read from the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserializeArray(double* double_t, size_t numElements, Endianness endianness); + + /*! + * @brief This function deserializes an array of long doubles. + * @param ldouble_t The variable that will store the array of long doubles read from the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserializeArray(long double* ldouble_t, size_t numElements); + + /*! + * @brief This function deserializes an array of long doubles with a different endianness. + * @param ldouble_t The variable that will store the array of long doubles read from the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserializeArray(long double* ldouble_t, size_t numElements, Endianness endianness); + + /*! + * @brief This function deserializes an array of booleans. + * @param bool_t The variable that will store the array of booleans read from the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + Cdr& deserializeArray(bool* bool_t, size_t numElements); + + /*! + * @brief This function deserializes an array of booleans with a different endianness. + * @param bool_t The variable that will store the array of booleans read from the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserializeArray(bool* bool_t, size_t numElements, Endianness endianness) { + (void)endianness; + return deserializeArray(bool_t, numElements); + } + + /*! + * @brief This function deserializes an array of strings. + * @param string_t The variable that will store the array of strings read from the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserializeArray(std::string* string_t, size_t numElements) { + for (size_t count = 0; count < numElements; ++count) { + deserialize(string_t[count]); + } + return *this; + } + + /*! + * @brief This function deserializes an array of wide-strings. + * @param string_t The variable that will store the array of wide-strings read from the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserializeArray(std::wstring* string_t, size_t numElements) { + for (size_t count = 0; count < numElements; ++count) { + deserialize(string_t[count]); + } + return *this; + } + + /*! + * @brief This function deserializes an array of strings with a different endianness. + * @param string_t The variable that will store the array of strings read from the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserializeArray(std::string* string_t, size_t numElements, Endianness endianness) { + bool auxSwap = m_swapBytes; + m_swapBytes = (m_swapBytes && (static_cast(m_endianness) == endianness)) || + (!m_swapBytes && (static_cast(m_endianness) != endianness)); + + try { + deserializeArray(string_t, numElements); + m_swapBytes = auxSwap; + } catch (eprosima::fastcdr::exception::Exception& ex) { + m_swapBytes = auxSwap; + ex.raise(); + } + + return *this; + } + + /*! + * @brief This function deserializes an array of wide-strings with a different endianness. + * @param string_t The variable that will store the array of wide-strings read from the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + inline Cdr& deserializeArray(std::wstring* string_t, size_t numElements, Endianness endianness) { + bool auxSwap = m_swapBytes; + m_swapBytes = (m_swapBytes && (static_cast(m_endianness) == endianness)) || + (!m_swapBytes && (static_cast(m_endianness) != endianness)); + + try { + deserializeArray(string_t, numElements); + m_swapBytes = auxSwap; + } catch (eprosima::fastcdr::exception::Exception& ex) { + m_swapBytes = auxSwap; + ex.raise(); + } + + return *this; + } + + /*! + * @brief This function deserializes an array of sequences of objects. + * @param vector_t The variable that will store the array of sequences of objects read from the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template + Cdr& deserializeArray(std::vector<_T, _Alloc>* vector_t, size_t numElements) { + for (size_t count = 0; count < numElements; ++count) { + deserialize(vector_t[count]); + } + return *this; + } + + /*! + * @brief This function template deserializes an array of non-basic objects. + * @param type_t The variable that will store the array of objects read from the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template + Cdr& deserializeArray(_T* type_t, size_t numElements) { + for (size_t count = 0; count < numElements; ++count) { + type_t[count].deserialize(*this); + } + return *this; + } + + /*! + * @brief This function template deserializes an array of non-basic objects with a different endianness. + * @param type_t The variable that will store the array of objects read from the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template + Cdr& deserializeArray(_T* type_t, size_t numElements, Endianness endianness) { + bool auxSwap = m_swapBytes; + m_swapBytes = (m_swapBytes && (static_cast(m_endianness) == endianness)) || + (!m_swapBytes && (static_cast(m_endianness) != endianness)); + + try { + deserializeArray(type_t, numElements); + m_swapBytes = auxSwap; + } catch (eprosima::fastcdr::exception::Exception& ex) { + m_swapBytes = auxSwap; + ex.raise(); + } + + return *this; + } + + /*! + * @brief This function template deserializes a string sequence. + * This function allocates memory to store the sequence. The user pointer will be set to point this allocated memory. + * The user will have to free this allocated memory using free() + * @param sequence_t The pointer that will store the sequence read from the buffer. + * @param numElements This variable return the number of elements of the sequence. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template + Cdr& deserializeSequence(std::string*& sequence_t, size_t& numElements) { + return deserializeStringSequence(sequence_t, numElements); + } + + /*! + * @brief This function template deserializes a wide-string sequence. + * This function allocates memory to store the sequence. The user pointer will be set to point this allocated memory. + * The user will have to free this allocated memory using free() + * @param sequence_t The pointer that will store the sequence read from the buffer. + * @param numElements This variable return the number of elements of the sequence. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template + Cdr& deserializeSequence(std::wstring*& sequence_t, size_t& numElements) { + return deserializeWStringSequence(sequence_t, numElements); + } + + /*! + * @brief This function template deserializes a raw sequence. + * This function allocates memory to store the sequence. The user pointer will be set to point this allocated memory. + * The user will have to free this allocated memory using free() + * @param sequence_t The pointer that will store the sequence read from the buffer. + * @param numElements This variable return the number of elements of the sequence. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template + Cdr& deserializeSequence(_T*& sequence_t, size_t& numElements) { + uint32_t seqLength = 0; + state state_before_error(*this); + + deserialize(seqLength); + + try { + sequence_t = reinterpret_cast<_T*>(calloc(seqLength, sizeof(_T))); + deserializeArray(sequence_t, seqLength); + } catch (eprosima::fastcdr::exception::Exception& ex) { + free(sequence_t); + sequence_t = NULL; + setState(state_before_error); + ex.raise(); + } + + numElements = seqLength; + return *this; + } + +#ifdef _MSC_VER + /*! + * @brief This function template deserializes a string sequence. + * This function allocates memory to store the sequence. The user pointer will be set to point this allocated memory. + * The user will have to free this allocated memory using free() + * @param sequence_t The pointer that will store the sequence read from the buffer. + * @param numElements This variable return the number of elements of the sequence. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template <> + Cdr& deserializeSequence(std::string*& sequence_t, size_t& numElements) { + return deserializeStringSequence(sequence_t, numElements); + } + + /*! + * @brief This function template deserializes a wide-string sequence. + * This function allocates memory to store the sequence. The user pointer will be set to point this allocated memory. + * The user will have to free this allocated memory using free() + * @param sequence_t The pointer that will store the sequence read from the buffer. + * @param numElements This variable return the number of elements of the sequence. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template <> + Cdr& deserializeSequence(std::wstring*& sequence_t, size_t& numElements) { + return deserializeWStringSequence(sequence_t, numElements); + } + +#endif // ifdef _MSC_VER + + /*! + * @brief This function template deserializes a raw sequence with a different endianness. + * This function allocates memory to store the sequence. The user pointer will be set to point this allocated memory. + * The user will have to free this allocated memory using free() + * @param sequence_t The pointer that will store the sequence read from the buffer. + * @param numElements This variable return the number of elements of the sequence. + * @param endianness Endianness that will be used in the deserialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template + Cdr& deserializeSequence(_T*& sequence_t, size_t& numElements, Endianness endianness) { + bool auxSwap = m_swapBytes; + m_swapBytes = (m_swapBytes && (static_cast(m_endianness) == endianness)) || + (!m_swapBytes && (static_cast(m_endianness) != endianness)); + + try { + deserializeSequence(sequence_t, numElements); + m_swapBytes = auxSwap; + } catch (eprosima::fastcdr::exception::Exception& ex) { + m_swapBytes = auxSwap; + ex.raise(); + } + + return *this; + } + +private: + Cdr(const Cdr&) = delete; + + Cdr& operator=(const Cdr&) = delete; + + Cdr& serializeBoolSequence(const std::vector& vector_t); + + Cdr& deserializeBoolSequence(std::vector& vector_t); + + Cdr& deserializeStringSequence(std::string*& sequence_t, size_t& numElements); + + Cdr& deserializeWStringSequence(std::wstring*& sequence_t, size_t& numElements); + + /*! + * @brief This function template detects the content type of the STD container array and serializes the array. + * @param array_t The array that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + template + Cdr& serializeArray(const std::array<_T, _Size>* array_t, size_t numElements) { + return serializeArray(array_t->data(), numElements * array_t->size()); + } + + /*! + * @brief This function template detects the content type of the STD container array and serializes the array with a + * different endianness. + * @param array_t The array that will be serialized in the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to serialize a position that + * exceeds the internal memory size. + */ + template + Cdr& serializeArray(const std::array<_T, _Size>* array_t, size_t numElements, Endianness endianness) { + return serializeArray(array_t->data(), numElements * array_t->size(), endianness); + } + + /*! + * @brief This function template detects the content type of the STD container array and deserializes the array. + * @param array_t The variable that will store the array read from the buffer. + * @param numElements Number of the elements in the array. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template + Cdr& deserializeArray(std::array<_T, _Size>* array_t, size_t numElements) { + return deserializeArray(array_t->data(), numElements * array_t->size()); + } + + /*! + * @brief This function template detects the content type of STD container array and deserializes the array with a + * different endianness. + * @param array_t The variable that will store the array read from the buffer. + * @param numElements Number of the elements in the array. + * @param endianness Endianness that will be used in the serialization of this value. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to deserialize a position that + * exceeds the internal memory size. + */ + template + Cdr& deserializeArray(std::array<_T, _Size>* array_t, size_t numElements, Endianness endianness) { + return deserializeArray(array_t->data(), numElements * array_t->size(), endianness); + } + + /*! + * @brief This function returns the extra bytes regarding the allignment. + * @param dataSize The size of the data that will be serialized. + * @return The size needed for the aligment. + */ + inline size_t alignment(size_t dataSize) const { + return dataSize > m_lastDataSize ? (dataSize - ((m_currentPosition - m_alignPosition) % dataSize)) & (dataSize - 1) + : 0; + } + + /*! + * @brief This function jumps the number of bytes of the alignment. These bytes should be calculated with the function + * eprosima::fastcdr::Cdr::alignment. + * @param align The number of bytes to be skipped. + */ + inline void makeAlign(size_t align) { + m_currentPosition += align; + } + + /*! + * @brief This function resizes the internal buffer. It only applies if the FastBuffer object was created with the + * default constructor. + * @param minSizeInc Minimun size increase for the internal buffer + * @return True if the resize was succesful, false if it was not + */ + bool resize(size_t minSizeInc); + + // TODO + const char* readString(uint32_t& length); + const std::wstring readWString(uint32_t& length); + + //! @brief Reference to the buffer that will be serialized/deserialized. + FastBuffer& m_cdrBuffer; + + //! @brief The type of CDR that will be use in serialization/deserialization. + CdrType m_cdrType; + + //! @brief Using DDS_CDR type, this attribute stores if the stream buffer contains a parameter list or not. + DDSCdrPlFlag m_plFlag; + + //! @brief This attribute stores the option flags when the CDR type is DDS_CDR; + uint16_t m_options; + + //! @brief The endianness that will be applied over the buffer. + uint8_t m_endianness; + + //! @brief This attribute specifies if it is needed to swap the bytes. + bool m_swapBytes; + + //! @brief Stores the last datasize serialized/deserialized. It's used to optimize. + size_t m_lastDataSize; + + //! @brief The current position in the serialization/deserialization process. + FastBuffer::iterator m_currentPosition; + + //! @brief The position from where the aligment is calculated. + FastBuffer::iterator m_alignPosition; + + //! @brief The last position in the buffer; + FastBuffer::iterator m_lastPosition; +}; +} // namespace fastcdr +} // namespace eprosima + +#endif // _CDR_CDR_H_ diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Accel.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Accel.cxx new file mode 100644 index 00000000000..10c74e1e912 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Accel.cxx @@ -0,0 +1,238 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Accel.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Accel.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +geometry_msgs::msg::Accel::Accel() +{ + // m_linear com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@7d0b7e3c + + // m_angular com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@7d0b7e3c + + +} + +geometry_msgs::msg::Accel::~Accel() +{ + +} + +geometry_msgs::msg::Accel::Accel( + const Accel& x) +{ + m_linear = x.m_linear; + m_angular = x.m_angular; +} + +geometry_msgs::msg::Accel::Accel( + Accel&& x) +{ + m_linear = std::move(x.m_linear); + m_angular = std::move(x.m_angular); +} + +geometry_msgs::msg::Accel& geometry_msgs::msg::Accel::operator =( + const Accel& x) +{ + + m_linear = x.m_linear; + m_angular = x.m_angular; + + return *this; +} + +geometry_msgs::msg::Accel& geometry_msgs::msg::Accel::operator =( + Accel&& x) +{ + + m_linear = std::move(x.m_linear); + m_angular = std::move(x.m_angular); + + return *this; +} + +bool geometry_msgs::msg::Accel::operator ==( + const Accel& x) const +{ + + return (m_linear == x.m_linear && m_angular == x.m_angular); +} + +bool geometry_msgs::msg::Accel::operator !=( + const Accel& x) const +{ + return !(*this == x); +} + +size_t geometry_msgs::msg::Accel::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += geometry_msgs::msg::Vector3::getMaxCdrSerializedSize(current_alignment); + current_alignment += geometry_msgs::msg::Vector3::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t geometry_msgs::msg::Accel::getCdrSerializedSize( + const geometry_msgs::msg::Accel& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += geometry_msgs::msg::Vector3::getCdrSerializedSize(data.linear(), current_alignment); + current_alignment += geometry_msgs::msg::Vector3::getCdrSerializedSize(data.angular(), current_alignment); + + return current_alignment - initial_alignment; +} + +void geometry_msgs::msg::Accel::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_linear; + scdr << m_angular; + +} + +void geometry_msgs::msg::Accel::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_linear; + dcdr >> m_angular; +} + +/*! + * @brief This function copies the value in member linear + * @param _linear New value to be copied in member linear + */ +void geometry_msgs::msg::Accel::linear( + const geometry_msgs::msg::Vector3& _linear) +{ + m_linear = _linear; +} + +/*! + * @brief This function moves the value in member linear + * @param _linear New value to be moved in member linear + */ +void geometry_msgs::msg::Accel::linear( + geometry_msgs::msg::Vector3&& _linear) +{ + m_linear = std::move(_linear); +} + +/*! + * @brief This function returns a constant reference to member linear + * @return Constant reference to member linear + */ +const geometry_msgs::msg::Vector3& geometry_msgs::msg::Accel::linear() const +{ + return m_linear; +} + +/*! + * @brief This function returns a reference to member linear + * @return Reference to member linear + */ +geometry_msgs::msg::Vector3& geometry_msgs::msg::Accel::linear() +{ + return m_linear; +} +/*! + * @brief This function copies the value in member angular + * @param _angular New value to be copied in member angular + */ +void geometry_msgs::msg::Accel::angular( + const geometry_msgs::msg::Vector3& _angular) +{ + m_angular = _angular; +} + +/*! + * @brief This function moves the value in member angular + * @param _angular New value to be moved in member angular + */ +void geometry_msgs::msg::Accel::angular( + geometry_msgs::msg::Vector3&& _angular) +{ + m_angular = std::move(_angular); +} + +/*! + * @brief This function returns a constant reference to member angular + * @return Constant reference to member angular + */ +const geometry_msgs::msg::Vector3& geometry_msgs::msg::Accel::angular() const +{ + return m_angular; +} + +/*! + * @brief This function returns a reference to member angular + * @return Reference to member angular + */ +geometry_msgs::msg::Vector3& geometry_msgs::msg::Accel::angular() +{ + return m_angular; +} + +size_t geometry_msgs::msg::Accel::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool geometry_msgs::msg::Accel::isKeyDefined() +{ + return false; +} + +void geometry_msgs::msg::Accel::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/types/Header.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Accel.h similarity index 56% rename from LibCarla/source/carla/ros2/types/Header.h rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Accel.h index 81a050caca3..eb08dbd8aad 100644 --- a/LibCarla/source/carla/ros2/types/Header.h +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Accel.h @@ -13,18 +13,16 @@ // limitations under the License. /*! - * @file Header.h + * @file Accel.h * This header file contains the declaration of the described types in the IDL file. * * This file was generated by the tool gen. */ -#ifndef _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADER_H_ -#define _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADER_H_ +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCEL_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCEL_H_ -#include "Time.h" - -#include +#include "Vector3.h" #include #include @@ -45,16 +43,16 @@ #if defined(_WIN32) #if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(Header_SOURCE) -#define Header_DllAPI __declspec( dllexport ) +#if defined(Accel_SOURCE) +#define Accel_DllAPI __declspec( dllexport ) #else -#define Header_DllAPI __declspec( dllimport ) -#endif // Header_SOURCE +#define Accel_DllAPI __declspec( dllimport ) +#endif // Accel_SOURCE #else -#define Header_DllAPI +#define Accel_DllAPI #endif // EPROSIMA_USER_DLL_EXPORT #else -#define Header_DllAPI +#define Accel_DllAPI #endif // _WIN32 namespace eprosima { @@ -63,125 +61,126 @@ class Cdr; } // namespace fastcdr } // namespace eprosima -namespace std_msgs { + +namespace geometry_msgs { namespace msg { /*! - * @brief This class represents the structure Header defined by the user in the IDL file. - * @ingroup HEADER + * @brief This class represents the structure Accel defined by the user in the IDL file. + * @ingroup ACCEL */ - class Header + class Accel { public: /*! * @brief Default constructor. */ - eProsima_user_DllExport Header(); + eProsima_user_DllExport Accel(); /*! * @brief Default destructor. */ - eProsima_user_DllExport ~Header(); + eProsima_user_DllExport ~Accel(); /*! * @brief Copy constructor. - * @param x Reference to the object std_msgs::msg::Header that will be copied. + * @param x Reference to the object geometry_msgs::msg::Accel that will be copied. */ - eProsima_user_DllExport Header( - const Header& x); + eProsima_user_DllExport Accel( + const Accel& x); /*! * @brief Move constructor. - * @param x Reference to the object std_msgs::msg::Header that will be copied. + * @param x Reference to the object geometry_msgs::msg::Accel that will be copied. */ - eProsima_user_DllExport Header( - Header&& x) noexcept; + eProsima_user_DllExport Accel( + Accel&& x); /*! * @brief Copy assignment. - * @param x Reference to the object std_msgs::msg::Header that will be copied. + * @param x Reference to the object geometry_msgs::msg::Accel that will be copied. */ - eProsima_user_DllExport Header& operator =( - const Header& x); + eProsima_user_DllExport Accel& operator =( + const Accel& x); /*! * @brief Move assignment. - * @param x Reference to the object std_msgs::msg::Header that will be copied. + * @param x Reference to the object geometry_msgs::msg::Accel that will be copied. */ - eProsima_user_DllExport Header& operator =( - Header&& x) noexcept; + eProsima_user_DllExport Accel& operator =( + Accel&& x); /*! * @brief Comparison operator. - * @param x std_msgs::msg::Header object to compare. + * @param x geometry_msgs::msg::Accel object to compare. */ eProsima_user_DllExport bool operator ==( - const Header& x) const; + const Accel& x) const; /*! * @brief Comparison operator. - * @param x std_msgs::msg::Header object to compare. + * @param x geometry_msgs::msg::Accel object to compare. */ eProsima_user_DllExport bool operator !=( - const Header& x) const; + const Accel& x) const; /*! - * @brief This function copies the value in member stamp - * @param _stamp New value to be copied in member stamp + * @brief This function copies the value in member linear + * @param _linear New value to be copied in member linear */ - eProsima_user_DllExport void stamp( - const builtin_interfaces::msg::Time& _stamp); + eProsima_user_DllExport void linear( + const geometry_msgs::msg::Vector3& _linear); /*! - * @brief This function moves the value in member stamp - * @param _stamp New value to be moved in member stamp + * @brief This function moves the value in member linear + * @param _linear New value to be moved in member linear */ - eProsima_user_DllExport void stamp( - builtin_interfaces::msg::Time&& _stamp); + eProsima_user_DllExport void linear( + geometry_msgs::msg::Vector3&& _linear); /*! - * @brief This function returns a constant reference to member stamp - * @return Constant reference to member stamp + * @brief This function returns a constant reference to member linear + * @return Constant reference to member linear */ - eProsima_user_DllExport const builtin_interfaces::msg::Time& stamp() const; + eProsima_user_DllExport const geometry_msgs::msg::Vector3& linear() const; /*! - * @brief This function returns a reference to member stamp - * @return Reference to member stamp + * @brief This function returns a reference to member linear + * @return Reference to member linear */ - eProsima_user_DllExport builtin_interfaces::msg::Time& stamp(); + eProsima_user_DllExport geometry_msgs::msg::Vector3& linear(); /*! - * @brief This function copies the value in member frame_id - * @param _frame_id New value to be copied in member frame_id + * @brief This function copies the value in member angular + * @param _angular New value to be copied in member angular */ - eProsima_user_DllExport void frame_id( - const std::string& _frame_id); + eProsima_user_DllExport void angular( + const geometry_msgs::msg::Vector3& _angular); /*! - * @brief This function moves the value in member frame_id - * @param _frame_id New value to be moved in member frame_id + * @brief This function moves the value in member angular + * @param _angular New value to be moved in member angular */ - eProsima_user_DllExport void frame_id( - std::string&& _frame_id); + eProsima_user_DllExport void angular( + geometry_msgs::msg::Vector3&& _angular); /*! - * @brief This function returns a constant reference to member frame_id - * @return Constant reference to member frame_id + * @brief This function returns a constant reference to member angular + * @return Constant reference to member angular */ - eProsima_user_DllExport const std::string& frame_id() const; + eProsima_user_DllExport const geometry_msgs::msg::Vector3& angular() const; /*! - * @brief This function returns a reference to member frame_id - * @return Reference to member frame_id + * @brief This function returns a reference to member angular + * @return Reference to member angular */ - eProsima_user_DllExport std::string& frame_id(); + eProsima_user_DllExport geometry_msgs::msg::Vector3& angular(); /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -192,9 +191,10 @@ namespace std_msgs { * @return Serialized size. */ eProsima_user_DllExport static size_t getCdrSerializedSize( - const std_msgs::msg::Header& data, + const geometry_msgs::msg::Accel& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -209,6 +209,8 @@ namespace std_msgs { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -231,10 +233,11 @@ namespace std_msgs { eprosima::fastcdr::Cdr& cdr) const; private: - builtin_interfaces::msg::Time m_stamp; - std::string m_frame_id; + + geometry_msgs::msg::Vector3 m_linear; + geometry_msgs::msg::Vector3 m_angular; }; } // namespace msg -} // namespace std_msgs +} // namespace geometry_msgs -#endif // _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADER_H_ +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCEL_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelPubSubTypes.cxx new file mode 100644 index 00000000000..ab7bd76ee39 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AccelPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "AccelPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace geometry_msgs { + namespace msg { + AccelPubSubType::AccelPubSubType() + { + setName("geometry_msgs::msg::dds_::Accel_"); + auto type_size = Accel::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = Accel::isKeyDefined(); + size_t keyLength = Accel::getKeyMaxCdrSerializedSize() > 16 ? + Accel::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + AccelPubSubType::~AccelPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool AccelPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + Accel* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool AccelPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + Accel* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function AccelPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* AccelPubSubType::createData() + { + return reinterpret_cast(new Accel()); + } + + void AccelPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool AccelPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + Accel* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + Accel::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || Accel::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace geometry_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelPubSubTypes.h new file mode 100644 index 00000000000..4e7a852de6f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AccelPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCEL_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCEL_PUBSUBTYPES_H_ + +#include +#include + +#include "Accel.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated Accel is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace geometry_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type Accel defined by the user in the IDL file. + * @ingroup ACCEL + */ + class AccelPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef Accel type; + + eProsima_user_DllExport AccelPubSubType(); + + eProsima_user_DllExport virtual ~AccelPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) Accel(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCEL_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovariance.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovariance.cxx new file mode 100644 index 00000000000..a00aa4ca240 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovariance.cxx @@ -0,0 +1,247 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AccelWithCovariance.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "AccelWithCovariance.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +geometry_msgs::msg::AccelWithCovariance::AccelWithCovariance() +{ + // m_accel com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@738dc9b + + // m_covariance com.eprosima.idl.parser.typecode.AliasTypeCode@3c77d488 + memset(&m_covariance, 0, (36) * 8); + +} + +geometry_msgs::msg::AccelWithCovariance::~AccelWithCovariance() +{ + +} + +geometry_msgs::msg::AccelWithCovariance::AccelWithCovariance( + const AccelWithCovariance& x) +{ + m_accel = x.m_accel; + m_covariance = x.m_covariance; +} + +geometry_msgs::msg::AccelWithCovariance::AccelWithCovariance( + AccelWithCovariance&& x) +{ + m_accel = std::move(x.m_accel); + m_covariance = std::move(x.m_covariance); +} + +geometry_msgs::msg::AccelWithCovariance& geometry_msgs::msg::AccelWithCovariance::operator =( + const AccelWithCovariance& x) +{ + + m_accel = x.m_accel; + m_covariance = x.m_covariance; + + return *this; +} + +geometry_msgs::msg::AccelWithCovariance& geometry_msgs::msg::AccelWithCovariance::operator =( + AccelWithCovariance&& x) +{ + + m_accel = std::move(x.m_accel); + m_covariance = std::move(x.m_covariance); + + return *this; +} + +bool geometry_msgs::msg::AccelWithCovariance::operator ==( + const AccelWithCovariance& x) const +{ + + return (m_accel == x.m_accel && m_covariance == x.m_covariance); +} + +bool geometry_msgs::msg::AccelWithCovariance::operator !=( + const AccelWithCovariance& x) const +{ + return !(*this == x); +} + +size_t geometry_msgs::msg::AccelWithCovariance::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += geometry_msgs::msg::Accel::getMaxCdrSerializedSize(current_alignment); + current_alignment += ((36) * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + + return current_alignment - initial_alignment; +} + +size_t geometry_msgs::msg::AccelWithCovariance::getCdrSerializedSize( + const geometry_msgs::msg::AccelWithCovariance& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += geometry_msgs::msg::Accel::getCdrSerializedSize(data.accel(), current_alignment); + if ((36) > 0) + { + current_alignment += ((36) * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + } + + + return current_alignment - initial_alignment; +} + +void geometry_msgs::msg::AccelWithCovariance::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_accel; + scdr << m_covariance; + + +} + +void geometry_msgs::msg::AccelWithCovariance::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_accel; + dcdr >> m_covariance; + +} + +/*! + * @brief This function copies the value in member accel + * @param _accel New value to be copied in member accel + */ +void geometry_msgs::msg::AccelWithCovariance::accel( + const geometry_msgs::msg::Accel& _accel) +{ + m_accel = _accel; +} + +/*! + * @brief This function moves the value in member accel + * @param _accel New value to be moved in member accel + */ +void geometry_msgs::msg::AccelWithCovariance::accel( + geometry_msgs::msg::Accel&& _accel) +{ + m_accel = std::move(_accel); +} + +/*! + * @brief This function returns a constant reference to member accel + * @return Constant reference to member accel + */ +const geometry_msgs::msg::Accel& geometry_msgs::msg::AccelWithCovariance::accel() const +{ + return m_accel; +} + +/*! + * @brief This function returns a reference to member accel + * @return Reference to member accel + */ +geometry_msgs::msg::Accel& geometry_msgs::msg::AccelWithCovariance::accel() +{ + return m_accel; +} +/*! + * @brief This function copies the value in member covariance + * @param _covariance New value to be copied in member covariance + */ +void geometry_msgs::msg::AccelWithCovariance::covariance( + const geometry_msgs::msg::double_accel_36& _covariance) +{ + m_covariance = _covariance; +} + +/*! + * @brief This function moves the value in member covariance + * @param _covariance New value to be moved in member covariance + */ +void geometry_msgs::msg::AccelWithCovariance::covariance( + geometry_msgs::msg::double_accel_36&& _covariance) +{ + m_covariance = std::move(_covariance); +} + +/*! + * @brief This function returns a constant reference to member covariance + * @return Constant reference to member covariance + */ +const geometry_msgs::msg::double_accel_36& geometry_msgs::msg::AccelWithCovariance::covariance() const +{ + return m_covariance; +} + +/*! + * @brief This function returns a reference to member covariance + * @return Reference to member covariance + */ +geometry_msgs::msg::double_accel_36& geometry_msgs::msg::AccelWithCovariance::covariance() +{ + return m_covariance; +} + +size_t geometry_msgs::msg::AccelWithCovariance::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool geometry_msgs::msg::AccelWithCovariance::isKeyDefined() +{ + return false; +} + +void geometry_msgs::msg::AccelWithCovariance::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovariance.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovariance.h new file mode 100644 index 00000000000..ff059f65813 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovariance.h @@ -0,0 +1,244 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AccelWithCovariance.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELWITHCOVARIANCE_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELWITHCOVARIANCE_H_ + +#include "Accel.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(AccelWithCovariance_SOURCE) +#define AccelWithCovariance_DllAPI __declspec( dllexport ) +#else +#define AccelWithCovariance_DllAPI __declspec( dllimport ) +#endif // AccelWithCovariance_SOURCE +#else +#define AccelWithCovariance_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define AccelWithCovariance_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace geometry_msgs { + namespace msg { + typedef std::array double_accel_36; + /*! + * @brief This class represents the structure AccelWithCovariance defined by the user in the IDL file. + * @ingroup ACCELWITHCOVARIANCE + */ + class AccelWithCovariance + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport AccelWithCovariance(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~AccelWithCovariance(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object geometry_msgs::msg::AccelWithCovariance that will be copied. + */ + eProsima_user_DllExport AccelWithCovariance( + const AccelWithCovariance& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object geometry_msgs::msg::AccelWithCovariance that will be copied. + */ + eProsima_user_DllExport AccelWithCovariance( + AccelWithCovariance&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object geometry_msgs::msg::AccelWithCovariance that will be copied. + */ + eProsima_user_DllExport AccelWithCovariance& operator =( + const AccelWithCovariance& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object geometry_msgs::msg::AccelWithCovariance that will be copied. + */ + eProsima_user_DllExport AccelWithCovariance& operator =( + AccelWithCovariance&& x); + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::AccelWithCovariance object to compare. + */ + eProsima_user_DllExport bool operator ==( + const AccelWithCovariance& x) const; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::AccelWithCovariance object to compare. + */ + eProsima_user_DllExport bool operator !=( + const AccelWithCovariance& x) const; + + /*! + * @brief This function copies the value in member accel + * @param _accel New value to be copied in member accel + */ + eProsima_user_DllExport void accel( + const geometry_msgs::msg::Accel& _accel); + + /*! + * @brief This function moves the value in member accel + * @param _accel New value to be moved in member accel + */ + eProsima_user_DllExport void accel( + geometry_msgs::msg::Accel&& _accel); + + /*! + * @brief This function returns a constant reference to member accel + * @return Constant reference to member accel + */ + eProsima_user_DllExport const geometry_msgs::msg::Accel& accel() const; + + /*! + * @brief This function returns a reference to member accel + * @return Reference to member accel + */ + eProsima_user_DllExport geometry_msgs::msg::Accel& accel(); + /*! + * @brief This function copies the value in member covariance + * @param _covariance New value to be copied in member covariance + */ + eProsima_user_DllExport void covariance( + const geometry_msgs::msg::double_accel_36& _covariance); + + /*! + * @brief This function moves the value in member covariance + * @param _covariance New value to be moved in member covariance + */ + eProsima_user_DllExport void covariance( + geometry_msgs::msg::double_accel_36&& _covariance); + + /*! + * @brief This function returns a constant reference to member covariance + * @return Constant reference to member covariance + */ + eProsima_user_DllExport const geometry_msgs::msg::double_accel_36& covariance() const; + + /*! + * @brief This function returns a reference to member covariance + * @return Reference to member covariance + */ + eProsima_user_DllExport geometry_msgs::msg::double_accel_36& covariance(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const geometry_msgs::msg::AccelWithCovariance& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + geometry_msgs::msg::Accel m_accel; + geometry_msgs::msg::double_accel_36 m_covariance; + }; + } // namespace msg +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELWITHCOVARIANCE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovariancePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovariancePubSubTypes.cxx new file mode 100644 index 00000000000..0447b9326fc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovariancePubSubTypes.cxx @@ -0,0 +1,177 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AccelWithCovariancePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "AccelWithCovariancePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace geometry_msgs { + namespace msg { + + AccelWithCovariancePubSubType::AccelWithCovariancePubSubType() + { + setName("geometry_msgs::msg::dds_::AccelWithCovariance_"); + auto type_size = AccelWithCovariance::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = AccelWithCovariance::isKeyDefined(); + size_t keyLength = AccelWithCovariance::getKeyMaxCdrSerializedSize() > 16 ? + AccelWithCovariance::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + AccelWithCovariancePubSubType::~AccelWithCovariancePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool AccelWithCovariancePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + AccelWithCovariance* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool AccelWithCovariancePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + AccelWithCovariance* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function AccelWithCovariancePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* AccelWithCovariancePubSubType::createData() + { + return reinterpret_cast(new AccelWithCovariance()); + } + + void AccelWithCovariancePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool AccelWithCovariancePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + AccelWithCovariance* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + AccelWithCovariance::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || AccelWithCovariance::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace geometry_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovariancePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovariancePubSubTypes.h new file mode 100644 index 00000000000..15c87c82c78 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovariancePubSubTypes.h @@ -0,0 +1,108 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file AccelWithCovariancePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELWITHCOVARIANCE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELWITHCOVARIANCE_PUBSUBTYPES_H_ + +#include +#include + +#include "AccelWithCovariance.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated AccelWithCovariance is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace geometry_msgs +{ + namespace msg + { + typedef std::array double_accel_36; + /*! + * @brief This class represents the TopicDataType of the type AccelWithCovariance defined by the user in the IDL file. + * @ingroup ACCELWITHCOVARIANCE + */ + class AccelWithCovariancePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef AccelWithCovariance type; + + eProsima_user_DllExport AccelWithCovariancePubSubType(); + + eProsima_user_DllExport virtual ~AccelWithCovariancePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) AccelWithCovariance(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELWITHCOVARIANCE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/Point.cpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point.cxx similarity index 86% rename from LibCarla/source/carla/ros2/types/Point.cpp rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point.cxx index ddb8fba9d85..b160f59cd8c 100644 --- a/LibCarla/source/carla/ros2/types/Point.cpp +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point.cxx @@ -34,21 +34,21 @@ using namespace eprosima::fastcdr::exception; #include -#define geometry_msgs_msg_Point_max_cdr_typesize 24ULL; -#define geometry_msgs_msg_Point_max_key_cdr_typesize 0ULL; - geometry_msgs::msg::Point::Point() { - // double m_x + // m_x com.eprosima.idl.parser.typecode.PrimitiveTypeCode@1e1a0406 m_x = 0.0; - // double m_y + // m_y com.eprosima.idl.parser.typecode.PrimitiveTypeCode@290222c1 m_y = 0.0; - // double m_z + // m_z com.eprosima.idl.parser.typecode.PrimitiveTypeCode@67f639d3 m_z = 0.0; + } geometry_msgs::msg::Point::~Point() { + + } geometry_msgs::msg::Point::Point( @@ -60,7 +60,7 @@ geometry_msgs::msg::Point::Point( } geometry_msgs::msg::Point::Point( - Point&& x) noexcept + Point&& x) { m_x = x.m_x; m_y = x.m_y; @@ -70,6 +70,7 @@ geometry_msgs::msg::Point::Point( geometry_msgs::msg::Point& geometry_msgs::msg::Point::operator =( const Point& x) { + m_x = x.m_x; m_y = x.m_y; m_z = x.m_z; @@ -78,8 +79,9 @@ geometry_msgs::msg::Point& geometry_msgs::msg::Point::operator =( } geometry_msgs::msg::Point& geometry_msgs::msg::Point::operator =( - Point&& x) noexcept + Point&& x) { + m_x = x.m_x; m_y = x.m_y; m_z = x.m_z; @@ -90,6 +92,7 @@ geometry_msgs::msg::Point& geometry_msgs::msg::Point::operator =( bool geometry_msgs::msg::Point::operator ==( const Point& x) const { + return (m_x == x.m_x && m_y == x.m_y && m_z == x.m_z); } @@ -102,8 +105,20 @@ bool geometry_msgs::msg::Point::operator !=( size_t geometry_msgs::msg::Point::getMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return geometry_msgs_msg_Point_max_cdr_typesize; + size_t initial_alignment = current_alignment; + + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + + return current_alignment - initial_alignment; } size_t geometry_msgs::msg::Point::getCdrSerializedSize( @@ -112,24 +127,35 @@ size_t geometry_msgs::msg::Point::getCdrSerializedSize( { (void)data; size_t initial_alignment = current_alignment; + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + return current_alignment - initial_alignment; } void geometry_msgs::msg::Point::serialize( eprosima::fastcdr::Cdr& scdr) const { + scdr << m_x; scdr << m_y; scdr << m_z; + } void geometry_msgs::msg::Point::deserialize( eprosima::fastcdr::Cdr& dcdr) { + dcdr >> m_x; dcdr >> m_y; dcdr >> m_z; @@ -219,11 +245,15 @@ double& geometry_msgs::msg::Point::z() return m_z; } + size_t geometry_msgs::msg::Point::getKeyMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return geometry_msgs_msg_Point_max_key_cdr_typesize; + size_t current_align = current_alignment; + + + + return current_align; } bool geometry_msgs::msg::Point::isKeyDefined() @@ -235,4 +265,7 @@ void geometry_msgs::msg::Point::serializeKey( eprosima::fastcdr::Cdr& scdr) const { (void) scdr; + } + + diff --git a/LibCarla/source/carla/ros2/types/Point.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point.h similarity index 94% rename from LibCarla/source/carla/ros2/types/Point.h rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point.h index 016955ff318..38cea0c8f44 100644 --- a/LibCarla/source/carla/ros2/types/Point.h +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point.h @@ -22,7 +22,6 @@ #ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT_H_ #define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT_H_ -#include #include #include @@ -61,6 +60,7 @@ class Cdr; } // namespace fastcdr } // namespace eprosima + namespace geometry_msgs { namespace msg { /*! @@ -93,7 +93,7 @@ namespace geometry_msgs { * @param x Reference to the object geometry_msgs::msg::Point that will be copied. */ eProsima_user_DllExport Point( - Point&& x) noexcept; + Point&& x); /*! * @brief Copy assignment. @@ -107,7 +107,7 @@ namespace geometry_msgs { * @param x Reference to the object geometry_msgs::msg::Point that will be copied. */ eProsima_user_DllExport Point& operator =( - Point&& x) noexcept; + Point&& x); /*! * @brief Comparison operator. @@ -180,12 +180,13 @@ namespace geometry_msgs { */ eProsima_user_DllExport double& z(); + /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -199,6 +200,7 @@ namespace geometry_msgs { const geometry_msgs::msg::Point& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -213,6 +215,8 @@ namespace geometry_msgs { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -235,6 +239,7 @@ namespace geometry_msgs { eprosima::fastcdr::Cdr& cdr) const; private: + double m_x; double m_y; double m_z; @@ -242,4 +247,4 @@ namespace geometry_msgs { } // namespace msg } // namespace geometry_msgs -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT_H_ +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/Point32.cpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32.cxx similarity index 86% rename from LibCarla/source/carla/ros2/types/Point32.cpp rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32.cxx index 0aa824cb038..9d779321703 100644 --- a/LibCarla/source/carla/ros2/types/Point32.cpp +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32.cxx @@ -34,21 +34,21 @@ using namespace eprosima::fastcdr::exception; #include -#define geometry_msgs_msg_Point32_max_cdr_typesize 12ULL; -#define geometry_msgs_msg_Point32_max_key_cdr_typesize 0ULL; - geometry_msgs::msg::Point32::Point32() { - // float m_x + // m_x com.eprosima.idl.parser.typecode.PrimitiveTypeCode@3012646b m_x = 0.0; - // float m_y + // m_y com.eprosima.idl.parser.typecode.PrimitiveTypeCode@4a883b15 m_y = 0.0; - // float m_z + // m_z com.eprosima.idl.parser.typecode.PrimitiveTypeCode@25641d39 m_z = 0.0; + } geometry_msgs::msg::Point32::~Point32() { + + } geometry_msgs::msg::Point32::Point32( @@ -60,7 +60,7 @@ geometry_msgs::msg::Point32::Point32( } geometry_msgs::msg::Point32::Point32( - Point32&& x) noexcept + Point32&& x) { m_x = x.m_x; m_y = x.m_y; @@ -70,6 +70,7 @@ geometry_msgs::msg::Point32::Point32( geometry_msgs::msg::Point32& geometry_msgs::msg::Point32::operator =( const Point32& x) { + m_x = x.m_x; m_y = x.m_y; m_z = x.m_z; @@ -78,8 +79,9 @@ geometry_msgs::msg::Point32& geometry_msgs::msg::Point32::operator =( } geometry_msgs::msg::Point32& geometry_msgs::msg::Point32::operator =( - Point32&& x) noexcept + Point32&& x) { + m_x = x.m_x; m_y = x.m_y; m_z = x.m_z; @@ -90,6 +92,7 @@ geometry_msgs::msg::Point32& geometry_msgs::msg::Point32::operator =( bool geometry_msgs::msg::Point32::operator ==( const Point32& x) const { + return (m_x == x.m_x && m_y == x.m_y && m_z == x.m_z); } @@ -102,8 +105,20 @@ bool geometry_msgs::msg::Point32::operator !=( size_t geometry_msgs::msg::Point32::getMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return geometry_msgs_msg_Point32_max_cdr_typesize; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + + return current_alignment - initial_alignment; } size_t geometry_msgs::msg::Point32::getCdrSerializedSize( @@ -112,24 +127,35 @@ size_t geometry_msgs::msg::Point32::getCdrSerializedSize( { (void)data; size_t initial_alignment = current_alignment; + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + return current_alignment - initial_alignment; } void geometry_msgs::msg::Point32::serialize( eprosima::fastcdr::Cdr& scdr) const { + scdr << m_x; scdr << m_y; scdr << m_z; + } void geometry_msgs::msg::Point32::deserialize( eprosima::fastcdr::Cdr& dcdr) { + dcdr >> m_x; dcdr >> m_y; dcdr >> m_z; @@ -219,11 +245,15 @@ float& geometry_msgs::msg::Point32::z() return m_z; } + size_t geometry_msgs::msg::Point32::getKeyMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return geometry_msgs_msg_Point32_max_key_cdr_typesize; + size_t current_align = current_alignment; + + + + return current_align; } bool geometry_msgs::msg::Point32::isKeyDefined() @@ -235,4 +265,7 @@ void geometry_msgs::msg::Point32::serializeKey( eprosima::fastcdr::Cdr& scdr) const { (void) scdr; + } + + diff --git a/LibCarla/source/carla/ros2/types/Point32.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32.h similarity index 94% rename from LibCarla/source/carla/ros2/types/Point32.h rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32.h index fbadcc6da30..8117cf9950c 100644 --- a/LibCarla/source/carla/ros2/types/Point32.h +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32.h @@ -22,7 +22,6 @@ #ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32_H_ #define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32_H_ -#include #include #include @@ -61,6 +60,7 @@ class Cdr; } // namespace fastcdr } // namespace eprosima + namespace geometry_msgs { namespace msg { /*! @@ -93,7 +93,7 @@ namespace geometry_msgs { * @param x Reference to the object geometry_msgs::msg::Point32 that will be copied. */ eProsima_user_DllExport Point32( - Point32&& x) noexcept; + Point32&& x); /*! * @brief Copy assignment. @@ -107,7 +107,7 @@ namespace geometry_msgs { * @param x Reference to the object geometry_msgs::msg::Point32 that will be copied. */ eProsima_user_DllExport Point32& operator =( - Point32&& x) noexcept; + Point32&& x); /*! * @brief Comparison operator. @@ -180,12 +180,13 @@ namespace geometry_msgs { */ eProsima_user_DllExport float& z(); + /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -199,6 +200,7 @@ namespace geometry_msgs { const geometry_msgs::msg::Point32& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -213,6 +215,8 @@ namespace geometry_msgs { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -235,6 +239,7 @@ namespace geometry_msgs { eprosima::fastcdr::Cdr& cdr) const; private: + float m_x; float m_y; float m_z; @@ -242,4 +247,4 @@ namespace geometry_msgs { } // namespace msg } // namespace geometry_msgs -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32_H_ +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/Point32PubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32PubSubTypes.cxx similarity index 89% rename from LibCarla/source/carla/ros2/types/Point32PubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32PubSubTypes.cxx index 8d852bee7c9..979bddb197e 100644 --- a/LibCarla/source/carla/ros2/types/Point32PubSubTypes.cpp +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32PubSubTypes.cxx @@ -19,6 +19,7 @@ * This file was generated by the tool fastcdrgen. */ + #include #include @@ -83,21 +84,21 @@ namespace geometry_msgs { SerializedPayload_t* payload, void* data) { - try - { - //Convert DATA to pointer of your type - Point32* p_type = static_cast(data); + //Convert DATA to pointer of your type + Point32* p_type = static_cast(data); - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); - // Deserialize encapsulation. - deser.read_encapsulation(); - payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + try + { // Deserialize the object. p_type->deserialize(deser); } @@ -168,5 +169,8 @@ namespace geometry_msgs { } return true; } + + } //End of namespace msg + } //End of namespace geometry_msgs diff --git a/LibCarla/source/carla/ros2/types/Point32PubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32PubSubTypes.h similarity index 76% rename from LibCarla/source/carla/ros2/types/Point32PubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32PubSubTypes.h index 17e59244c6e..346f91f5d4d 100644 --- a/LibCarla/source/carla/ros2/types/Point32PubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32PubSubTypes.h @@ -19,6 +19,7 @@ * This file was generated by the tool fastcdrgen. */ + #ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32_PUBSUBTYPES_H_ #define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32_PUBSUBTYPES_H_ @@ -36,35 +37,6 @@ namespace geometry_msgs { namespace msg { - #ifndef SWIG - namespace detail { - - template - struct Point32_rob - { - friend constexpr typename Tag::type get( - Tag) - { - return M; - } - }; - - struct Point32_f - { - typedef float Point32::* type; - friend constexpr type get( - Point32_f); - }; - - template struct Point32_rob; - - template - inline size_t constexpr Point32_offset_of() { - return ((::size_t) &reinterpret_cast((((T*)0)->*get(Tag())))); - } - } - #endif - /*! * @brief This class represents the TopicDataType of the type Point32 defined by the user in the IDL file. * @ingroup POINT32 @@ -77,7 +49,7 @@ namespace geometry_msgs eProsima_user_DllExport Point32PubSubType(); - eProsima_user_DllExport virtual ~Point32PubSubType() override; + eProsima_user_DllExport virtual ~Point32PubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -111,7 +83,7 @@ namespace geometry_msgs #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN eProsima_user_DllExport inline bool is_plain() const override { - return is_plain_impl(); + return true; } #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN @@ -125,14 +97,11 @@ namespace geometry_msgs } #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; unsigned char* m_keyBuffer; - private: - static constexpr bool is_plain_impl() - { - return 12ULL == (detail::Point32_offset_of() + sizeof(float)); - }}; + }; } } -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/PointPubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PointPubSubTypes.cxx similarity index 89% rename from LibCarla/source/carla/ros2/types/PointPubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PointPubSubTypes.cxx index cd97d27192d..6c69a36b12a 100644 --- a/LibCarla/source/carla/ros2/types/PointPubSubTypes.cpp +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PointPubSubTypes.cxx @@ -19,6 +19,7 @@ * This file was generated by the tool fastcdrgen. */ + #include #include @@ -83,21 +84,21 @@ namespace geometry_msgs { SerializedPayload_t* payload, void* data) { - try - { - //Convert DATA to pointer of your type - Point* p_type = static_cast(data); + //Convert DATA to pointer of your type + Point* p_type = static_cast(data); - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); - // Deserialize encapsulation. - deser.read_encapsulation(); - payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + try + { // Deserialize the object. p_type->deserialize(deser); } @@ -168,5 +169,8 @@ namespace geometry_msgs { } return true; } + + } //End of namespace msg + } //End of namespace geometry_msgs diff --git a/LibCarla/source/carla/ros2/types/PointPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PointPubSubTypes.h similarity index 75% rename from LibCarla/source/carla/ros2/types/PointPubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PointPubSubTypes.h index f6c2900f980..241f4d4b9e9 100644 --- a/LibCarla/source/carla/ros2/types/PointPubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PointPubSubTypes.h @@ -19,6 +19,7 @@ * This file was generated by the tool fastcdrgen. */ + #ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT_PUBSUBTYPES_H_ #define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT_PUBSUBTYPES_H_ @@ -36,35 +37,6 @@ namespace geometry_msgs { namespace msg { - #ifndef SWIG - namespace detail { - - template - struct Point_rob - { - friend constexpr typename Tag::type get( - Tag) - { - return M; - } - }; - - struct Point_f - { - typedef double Point::* type; - friend constexpr type get( - Point_f); - }; - - template struct Point_rob; - - template - inline size_t constexpr Point_offset_of() { - return ((::size_t) &reinterpret_cast((((T*)0)->*get(Tag())))); - } - } - #endif - /*! * @brief This class represents the TopicDataType of the type Point defined by the user in the IDL file. * @ingroup POINT @@ -77,7 +49,7 @@ namespace geometry_msgs eProsima_user_DllExport PointPubSubType(); - eProsima_user_DllExport virtual ~PointPubSubType() override; + eProsima_user_DllExport virtual ~PointPubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -111,7 +83,7 @@ namespace geometry_msgs #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN eProsima_user_DllExport inline bool is_plain() const override { - return is_plain_impl(); + return true; } #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN @@ -128,15 +100,8 @@ namespace geometry_msgs MD5 m_md5; unsigned char* m_keyBuffer; - - private: - - static constexpr bool is_plain_impl() - { - return 24ULL == (detail::Point_offset_of() + sizeof(double)); - - }}; + }; } } -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Polygon.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Polygon.cxx new file mode 100644 index 00000000000..7f3821c9019 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Polygon.cxx @@ -0,0 +1,198 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Polygon.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Polygon.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +geometry_msgs::msg::Polygon::Polygon() +{ + // m_points com.eprosima.idl.parser.typecode.SequenceTypeCode@b9b00e0 + + +} + +geometry_msgs::msg::Polygon::~Polygon() +{ +} + +geometry_msgs::msg::Polygon::Polygon( + const Polygon& x) +{ + m_points = x.m_points; +} + +geometry_msgs::msg::Polygon::Polygon( + Polygon&& x) +{ + m_points = std::move(x.m_points); +} + +geometry_msgs::msg::Polygon& geometry_msgs::msg::Polygon::operator =( + const Polygon& x) +{ + + m_points = x.m_points; + + return *this; +} + +geometry_msgs::msg::Polygon& geometry_msgs::msg::Polygon::operator =( + Polygon&& x) +{ + + m_points = std::move(x.m_points); + + return *this; +} + +bool geometry_msgs::msg::Polygon::operator ==( + const Polygon& x) const +{ + + return (m_points == x.m_points); +} + +bool geometry_msgs::msg::Polygon::operator !=( + const Polygon& x) const +{ + return !(*this == x); +} + +size_t geometry_msgs::msg::Polygon::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < 100; ++a) + { + current_alignment += geometry_msgs::msg::Point32::getMaxCdrSerializedSize(current_alignment);} + + return current_alignment - initial_alignment; +} + +size_t geometry_msgs::msg::Polygon::getCdrSerializedSize( + const geometry_msgs::msg::Polygon& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + + for(size_t a = 0; a < data.points().size(); ++a) + { + current_alignment += geometry_msgs::msg::Point32::getCdrSerializedSize(data.points().at(a), current_alignment);} + + return current_alignment - initial_alignment; +} + +void geometry_msgs::msg::Polygon::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_points; +} + +void geometry_msgs::msg::Polygon::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_points;} + +/*! + * @brief This function copies the value in member points + * @param _points New value to be copied in member points + */ +void geometry_msgs::msg::Polygon::points( + const std::vector& _points) +{ + m_points = _points; +} + +/*! + * @brief This function moves the value in member points + * @param _points New value to be moved in member points + */ +void geometry_msgs::msg::Polygon::points( + std::vector&& _points) +{ + m_points = std::move(_points); +} + +/*! + * @brief This function returns a constant reference to member points + * @return Constant reference to member points + */ +const std::vector& geometry_msgs::msg::Polygon::points() const +{ + return m_points; +} + +/*! + * @brief This function returns a reference to member points + * @return Reference to member points + */ +std::vector& geometry_msgs::msg::Polygon::points() +{ + return m_points; +} + +size_t geometry_msgs::msg::Polygon::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool geometry_msgs::msg::Polygon::isKeyDefined() +{ + return false; +} + +void geometry_msgs::msg::Polygon::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/types/TFMessage.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Polygon.h similarity index 60% rename from LibCarla/source/carla/ros2/types/TFMessage.h rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Polygon.h index adb9e9a7954..fe1202ebf6b 100644 --- a/LibCarla/source/carla/ros2/types/TFMessage.h +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Polygon.h @@ -13,18 +13,16 @@ // limitations under the License. /*! - * @file TFMessage.h + * @file Polygon.h * This header file contains the declaration of the described types in the IDL file. * * This file was generated by the tool gen. */ -#ifndef _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGE_H_ -#define _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGE_H_ +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POLYGON_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POLYGON_H_ -#include "TransformStamped.h" - -#include +#include "Point32.h" #include #include @@ -45,16 +43,16 @@ #if defined(_WIN32) #if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(TFMessage_SOURCE) -#define TFMessage_DllAPI __declspec( dllexport ) +#if defined(Polygon_SOURCE) +#define Polygon_DllAPI __declspec( dllexport ) #else -#define TFMessage_DllAPI __declspec( dllimport ) -#endif // TFMessage_SOURCE +#define Polygon_DllAPI __declspec( dllimport ) +#endif // Polygon_SOURCE #else -#define TFMessage_DllAPI +#define Polygon_DllAPI #endif // EPROSIMA_USER_DLL_EXPORT #else -#define TFMessage_DllAPI +#define Polygon_DllAPI #endif // _WIN32 namespace eprosima { @@ -64,100 +62,100 @@ class Cdr; } // namespace eprosima -namespace tf2_msgs { +namespace geometry_msgs { namespace msg { /*! - * @brief This class represents the structure TFMessage defined by the user in the IDL file. - * @ingroup TFMESSAGE + * @brief This class represents the structure Polygon defined by the user in the IDL file. + * @ingroup POLYGON */ - class TFMessage + class Polygon { public: /*! * @brief Default constructor. */ - eProsima_user_DllExport TFMessage(); + eProsima_user_DllExport Polygon(); /*! * @brief Default destructor. */ - eProsima_user_DllExport ~TFMessage(); + eProsima_user_DllExport ~Polygon(); /*! * @brief Copy constructor. - * @param x Reference to the object tf2_msgs::msg::TFMessage that will be copied. + * @param x Reference to the object geometry_msgs::msg::Polygon that will be copied. */ - eProsima_user_DllExport TFMessage( - const TFMessage& x); + eProsima_user_DllExport Polygon( + const Polygon& x); /*! * @brief Move constructor. - * @param x Reference to the object tf2_msgs::msg::TFMessage that will be copied. + * @param x Reference to the object geometry_msgs::msg::Polygon that will be copied. */ - eProsima_user_DllExport TFMessage( - TFMessage&& x) noexcept; + eProsima_user_DllExport Polygon( + Polygon&& x); /*! * @brief Copy assignment. - * @param x Reference to the object tf2_msgs::msg::TFMessage that will be copied. + * @param x Reference to the object geometry_msgs::msg::Polygon that will be copied. */ - eProsima_user_DllExport TFMessage& operator =( - const TFMessage& x); + eProsima_user_DllExport Polygon& operator =( + const Polygon& x); /*! * @brief Move assignment. - * @param x Reference to the object tf2_msgs::msg::TFMessage that will be copied. + * @param x Reference to the object geometry_msgs::msg::Polygon that will be copied. */ - eProsima_user_DllExport TFMessage& operator =( - TFMessage&& x) noexcept; + eProsima_user_DllExport Polygon& operator =( + Polygon&& x); /*! * @brief Comparison operator. - * @param x tf2_msgs::msg::TFMessage object to compare. + * @param x geometry_msgs::msg::Polygon object to compare. */ eProsima_user_DllExport bool operator ==( - const TFMessage& x) const; + const Polygon& x) const; /*! * @brief Comparison operator. - * @param x tf2_msgs::msg::TFMessage object to compare. + * @param x geometry_msgs::msg::Polygon object to compare. */ eProsima_user_DllExport bool operator !=( - const TFMessage& x) const; + const Polygon& x) const; /*! - * @brief This function copies the value in member transforms - * @param _transforms New value to be copied in member transforms + * @brief This function copies the value in member points + * @param _points New value to be copied in member points */ - eProsima_user_DllExport void transforms( - const std::vector& _transforms); + eProsima_user_DllExport void points( + const std::vector& _points); /*! - * @brief This function moves the value in member transforms - * @param _transforms New value to be moved in member transforms + * @brief This function moves the value in member points + * @param _points New value to be moved in member points */ - eProsima_user_DllExport void transforms( - std::vector&& _transforms); + eProsima_user_DllExport void points( + std::vector&& _points); /*! - * @brief This function returns a constant reference to member transforms - * @return Constant reference to member transforms + * @brief This function returns a constant reference to member points + * @return Constant reference to member points */ - eProsima_user_DllExport const std::vector& transforms() const; + eProsima_user_DllExport const std::vector& points() const; /*! - * @brief This function returns a reference to member transforms - * @return Reference to member transforms + * @brief This function returns a reference to member points + * @return Reference to member points */ - eProsima_user_DllExport std::vector& transforms(); + eProsima_user_DllExport std::vector& points(); /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -168,9 +166,10 @@ namespace tf2_msgs { * @return Serialized size. */ eProsima_user_DllExport static size_t getCdrSerializedSize( - const tf2_msgs::msg::TFMessage& data, + const geometry_msgs::msg::Polygon& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -185,6 +184,8 @@ namespace tf2_msgs { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -207,10 +208,10 @@ namespace tf2_msgs { eprosima::fastcdr::Cdr& cdr) const; private: - std::vector m_transforms; + std::vector m_points; }; } // namespace msg -} // namespace tf2_msgs +} // namespace geometry_msgs -#endif // _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGE_H_ +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POLYGON_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PolygonPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PolygonPubSubTypes.cxx new file mode 100644 index 00000000000..671dbdfd821 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PolygonPubSubTypes.cxx @@ -0,0 +1,176 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PolygonPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "PolygonPubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace geometry_msgs { + namespace msg { + PolygonPubSubType::PolygonPubSubType() + { + setName("geometry_msgs::msg::dds_::Polygon_"); + auto type_size = Polygon::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = Polygon::isKeyDefined(); + size_t keyLength = Polygon::getKeyMaxCdrSerializedSize() > 16 ? + Polygon::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + PolygonPubSubType::~PolygonPubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool PolygonPubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + Polygon* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool PolygonPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + Polygon* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function PolygonPubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* PolygonPubSubType::createData() + { + return reinterpret_cast(new Polygon()); + } + + void PolygonPubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool PolygonPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + Polygon* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + Polygon::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || Polygon::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace geometry_msgs diff --git a/LibCarla/source/carla/ros2/types/ImagePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PolygonPubSubTypes.h similarity index 80% rename from LibCarla/source/carla/ros2/types/ImagePubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PolygonPubSubTypes.h index 499844880ac..f621ad859dd 100644 --- a/LibCarla/source/carla/ros2/types/ImagePubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PolygonPubSubTypes.h @@ -13,42 +13,43 @@ // limitations under the License. /*! - * @file ImagePubSubTypes.h + * @file PolygonPubSubTypes.h * This header file contains the declaration of the serialization functions. * * This file was generated by the tool fastcdrgen. */ -#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGE_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGE_PUBSUBTYPES_H_ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POLYGON_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POLYGON_PUBSUBTYPES_H_ #include #include -#include "Image.h" +#include "Polygon.h" #if !defined(GEN_API_VER) || (GEN_API_VER != 1) #error \ - Generated Image is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. + Generated Polygon is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. #endif // GEN_API_VER -namespace sensor_msgs +namespace geometry_msgs { namespace msg { /*! - * @brief This class represents the TopicDataType of the type Image defined by the user in the IDL file. - * @ingroup IMAGE + * @brief This class represents the TopicDataType of the type Polygon defined by the user in the IDL file. + * @ingroup POLYGON */ - class ImagePubSubType : public eprosima::fastdds::dds::TopicDataType + class PolygonPubSubType : public eprosima::fastdds::dds::TopicDataType { public: - typedef Image type; + typedef Polygon type; - eProsima_user_DllExport ImagePubSubType(); + eProsima_user_DllExport PolygonPubSubType(); - eProsima_user_DllExport virtual ~ImagePubSubType() override; + eProsima_user_DllExport virtual ~PolygonPubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -96,10 +97,11 @@ namespace sensor_msgs } #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; unsigned char* m_keyBuffer; }; } } -#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGE_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POLYGON_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/Pose.cpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Pose.cxx similarity index 89% rename from LibCarla/source/carla/ros2/types/Pose.cpp rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Pose.cxx index d643cd126ec..04a4cccfc48 100644 --- a/LibCarla/source/carla/ros2/types/Pose.cpp +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Pose.cxx @@ -34,19 +34,18 @@ using namespace eprosima::fastcdr::exception; #include -#define geometry_msgs_msg_Pose_max_cdr_typesize 56ULL; -#define geometry_msgs_msg_Point_max_cdr_typesize 24ULL; -#define geometry_msgs_msg_Quaternion_max_cdr_typesize 32ULL; -#define geometry_msgs_msg_Pose_max_key_cdr_typesize 0ULL; -#define geometry_msgs_msg_Point_max_key_cdr_typesize 0ULL; -#define geometry_msgs_msg_Quaternion_max_key_cdr_typesize 0ULL; - geometry_msgs::msg::Pose::Pose() { + // m_position com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@6cd28fa7 + + // m_orientation com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@614ca7df + + } geometry_msgs::msg::Pose::~Pose() { + } geometry_msgs::msg::Pose::Pose( @@ -57,7 +56,7 @@ geometry_msgs::msg::Pose::Pose( } geometry_msgs::msg::Pose::Pose( - Pose&& x) noexcept + Pose&& x) { m_position = std::move(x.m_position); m_orientation = std::move(x.m_orientation); @@ -66,6 +65,7 @@ geometry_msgs::msg::Pose::Pose( geometry_msgs::msg::Pose& geometry_msgs::msg::Pose::operator =( const Pose& x) { + m_position = x.m_position; m_orientation = x.m_orientation; @@ -73,8 +73,9 @@ geometry_msgs::msg::Pose& geometry_msgs::msg::Pose::operator =( } geometry_msgs::msg::Pose& geometry_msgs::msg::Pose::operator =( - Pose&& x) noexcept + Pose&& x) { + m_position = std::move(x.m_position); m_orientation = std::move(x.m_orientation); @@ -84,6 +85,7 @@ geometry_msgs::msg::Pose& geometry_msgs::msg::Pose::operator =( bool geometry_msgs::msg::Pose::operator ==( const Pose& x) const { + return (m_position == x.m_position && m_orientation == x.m_orientation); } @@ -96,15 +98,23 @@ bool geometry_msgs::msg::Pose::operator !=( size_t geometry_msgs::msg::Pose::getMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return geometry_msgs_msg_Pose_max_cdr_typesize; + size_t initial_alignment = current_alignment; + + + current_alignment += geometry_msgs::msg::Point::getMaxCdrSerializedSize(current_alignment); + current_alignment += geometry_msgs::msg::Quaternion::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; } size_t geometry_msgs::msg::Pose::getCdrSerializedSize( const geometry_msgs::msg::Pose& data, size_t current_alignment) { + (void)data; size_t initial_alignment = current_alignment; + + current_alignment += geometry_msgs::msg::Point::getCdrSerializedSize(data.position(), current_alignment); current_alignment += geometry_msgs::msg::Quaternion::getCdrSerializedSize(data.orientation(), current_alignment); @@ -114,13 +124,16 @@ size_t geometry_msgs::msg::Pose::getCdrSerializedSize( void geometry_msgs::msg::Pose::serialize( eprosima::fastcdr::Cdr& scdr) const { + scdr << m_position; scdr << m_orientation; + } void geometry_msgs::msg::Pose::deserialize( eprosima::fastcdr::Cdr& dcdr) { + dcdr >> m_position; dcdr >> m_orientation; } @@ -162,7 +175,6 @@ geometry_msgs::msg::Point& geometry_msgs::msg::Pose::position() { return m_position; } - /*! * @brief This function copies the value in member orientation * @param _orientation New value to be copied in member orientation @@ -201,12 +213,14 @@ geometry_msgs::msg::Quaternion& geometry_msgs::msg::Pose::orientation() return m_orientation; } - size_t geometry_msgs::msg::Pose::getKeyMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return geometry_msgs_msg_Pose_max_key_cdr_typesize; + size_t current_align = current_alignment; + + + + return current_align; } bool geometry_msgs::msg::Pose::isKeyDefined() @@ -218,4 +232,7 @@ void geometry_msgs::msg::Pose::serializeKey( eprosima::fastcdr::Cdr& scdr) const { (void) scdr; + } + + diff --git a/LibCarla/source/carla/ros2/types/Pose.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Pose.h similarity index 94% rename from LibCarla/source/carla/ros2/types/Pose.h rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Pose.h index 87060b15e47..d21efb6beb3 100644 --- a/LibCarla/source/carla/ros2/types/Pose.h +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Pose.h @@ -22,10 +22,8 @@ #ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSE_H_ #define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSE_H_ -#include "Point.h" #include "Quaternion.h" - -#include +#include "Point.h" #include #include @@ -64,6 +62,7 @@ class Cdr; } // namespace fastcdr } // namespace eprosima + namespace geometry_msgs { namespace msg { /*! @@ -96,7 +95,7 @@ namespace geometry_msgs { * @param x Reference to the object geometry_msgs::msg::Pose that will be copied. */ eProsima_user_DllExport Pose( - Pose&& x) noexcept; + Pose&& x); /*! * @brief Copy assignment. @@ -110,7 +109,7 @@ namespace geometry_msgs { * @param x Reference to the object geometry_msgs::msg::Pose that will be copied. */ eProsima_user_DllExport Pose& operator =( - Pose&& x) noexcept; + Pose&& x); /*! * @brief Comparison operator. @@ -178,11 +177,11 @@ namespace geometry_msgs { eProsima_user_DllExport geometry_msgs::msg::Quaternion& orientation(); /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -196,6 +195,7 @@ namespace geometry_msgs { const geometry_msgs::msg::Pose& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -210,6 +210,8 @@ namespace geometry_msgs { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -232,10 +234,11 @@ namespace geometry_msgs { eprosima::fastcdr::Cdr& cdr) const; private: + geometry_msgs::msg::Point m_position; geometry_msgs::msg::Quaternion m_orientation; }; } // namespace msg } // namespace geometry_msgs -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSE_H_ +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/PosePubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PosePubSubTypes.cxx similarity index 89% rename from LibCarla/source/carla/ros2/types/PosePubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PosePubSubTypes.cxx index a4587eb82c4..9cc1f414fb7 100644 --- a/LibCarla/source/carla/ros2/types/PosePubSubTypes.cpp +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PosePubSubTypes.cxx @@ -19,6 +19,7 @@ * This file was generated by the tool fastcdrgen. */ + #include #include @@ -83,21 +84,21 @@ namespace geometry_msgs { SerializedPayload_t* payload, void* data) { - try - { - //Convert DATA to pointer of your type - Pose* p_type = static_cast(data); + //Convert DATA to pointer of your type + Pose* p_type = static_cast(data); - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); - // Deserialize encapsulation. - deser.read_encapsulation(); - payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + try + { // Deserialize the object. p_type->deserialize(deser); } @@ -168,5 +169,8 @@ namespace geometry_msgs { } return true; } + + } //End of namespace msg + } //End of namespace geometry_msgs diff --git a/LibCarla/source/carla/ros2/types/TimePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PosePubSubTypes.h similarity index 80% rename from LibCarla/source/carla/ros2/types/TimePubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PosePubSubTypes.h index 9a2a4d9a8c8..3cdddb9946d 100644 --- a/LibCarla/source/carla/ros2/types/TimePubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PosePubSubTypes.h @@ -13,42 +13,43 @@ // limitations under the License. /*! - * @file TimePubSubTypes.h + * @file PosePubSubTypes.h * This header file contains the declaration of the serialization functions. * * This file was generated by the tool fastcdrgen. */ -#ifndef _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIME_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIME_PUBSUBTYPES_H_ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSE_PUBSUBTYPES_H_ #include #include -#include "Time.h" +#include "Pose.h" #if !defined(GEN_API_VER) || (GEN_API_VER != 1) #error \ - Generated Time is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. + Generated Pose is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. #endif // GEN_API_VER -namespace builtin_interfaces +namespace geometry_msgs { namespace msg { /*! - * @brief This class represents the TopicDataType of the type Time defined by the user in the IDL file. - * @ingroup TIME + * @brief This class represents the TopicDataType of the type Pose defined by the user in the IDL file. + * @ingroup POSE */ - class TimePubSubType : public eprosima::fastdds::dds::TopicDataType + class PosePubSubType : public eprosima::fastdds::dds::TopicDataType { public: - typedef Time type; + typedef Pose type; - eProsima_user_DllExport TimePubSubType(); + eProsima_user_DllExport PosePubSubType(); - eProsima_user_DllExport virtual ~TimePubSubType() override; + eProsima_user_DllExport virtual ~PosePubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -91,15 +92,16 @@ namespace builtin_interfaces eProsima_user_DllExport inline bool construct_sample( void* memory) const override { - new (memory) Time(); + new (memory) Pose(); return true; } #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; unsigned char* m_keyBuffer; }; } } -#endif // _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIME_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/PoseWithCovariance.cpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariance.cxx similarity index 78% rename from LibCarla/source/carla/ros2/types/PoseWithCovariance.cpp rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariance.cxx index 83e52a52539..0e89095fd2a 100644 --- a/LibCarla/source/carla/ros2/types/PoseWithCovariance.cpp +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariance.cxx @@ -34,25 +34,19 @@ using namespace eprosima::fastcdr::exception; #include -#define geometry_msgs_msg_Pose_max_cdr_typesize 56ULL; -#define geometry_msgs_msg_Point_max_cdr_typesize 24ULL; -#define geometry_msgs_msg_PoseWithCovariance_max_cdr_typesize 344ULL; -#define geometry_msgs_msg_Quaternion_max_cdr_typesize 32ULL; -#define geometry_msgs_msg_Pose_max_key_cdr_typesize 0ULL; -#define geometry_msgs_msg_Point_max_key_cdr_typesize 0ULL; -#define geometry_msgs_msg_PoseWithCovariance_max_key_cdr_typesize 0ULL; -#define geometry_msgs_msg_Quaternion_max_key_cdr_typesize 0ULL; geometry_msgs::msg::PoseWithCovariance::PoseWithCovariance() { - // geometry_msgs::msg::Pose m_pose + // m_pose com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@4efc180e - // geometry_msgs::msg::geometry_msgs__PoseWithCovariance__double_array_36 m_covariance + // m_covariance com.eprosima.idl.parser.typecode.AliasTypeCode@bd4dc25 memset(&m_covariance, 0, (36) * 8); + } geometry_msgs::msg::PoseWithCovariance::~PoseWithCovariance() { + } geometry_msgs::msg::PoseWithCovariance::PoseWithCovariance( @@ -63,7 +57,7 @@ geometry_msgs::msg::PoseWithCovariance::PoseWithCovariance( } geometry_msgs::msg::PoseWithCovariance::PoseWithCovariance( - PoseWithCovariance&& x) noexcept + PoseWithCovariance&& x) { m_pose = std::move(x.m_pose); m_covariance = std::move(x.m_covariance); @@ -72,6 +66,7 @@ geometry_msgs::msg::PoseWithCovariance::PoseWithCovariance( geometry_msgs::msg::PoseWithCovariance& geometry_msgs::msg::PoseWithCovariance::operator =( const PoseWithCovariance& x) { + m_pose = x.m_pose; m_covariance = x.m_covariance; @@ -79,8 +74,9 @@ geometry_msgs::msg::PoseWithCovariance& geometry_msgs::msg::PoseWithCovariance:: } geometry_msgs::msg::PoseWithCovariance& geometry_msgs::msg::PoseWithCovariance::operator =( - PoseWithCovariance&& x) noexcept + PoseWithCovariance&& x) { + m_pose = std::move(x.m_pose); m_covariance = std::move(x.m_covariance); @@ -90,6 +86,7 @@ geometry_msgs::msg::PoseWithCovariance& geometry_msgs::msg::PoseWithCovariance:: bool geometry_msgs::msg::PoseWithCovariance::operator ==( const PoseWithCovariance& x) const { + return (m_pose == x.m_pose && m_covariance == x.m_covariance); } @@ -102,17 +99,31 @@ bool geometry_msgs::msg::PoseWithCovariance::operator !=( size_t geometry_msgs::msg::PoseWithCovariance::getMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return geometry_msgs_msg_PoseWithCovariance_max_cdr_typesize; + size_t initial_alignment = current_alignment; + + + current_alignment += geometry_msgs::msg::Pose::getMaxCdrSerializedSize(current_alignment); + current_alignment += ((36) * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + + return current_alignment - initial_alignment; } size_t geometry_msgs::msg::PoseWithCovariance::getCdrSerializedSize( const geometry_msgs::msg::PoseWithCovariance& data, size_t current_alignment) { + (void)data; size_t initial_alignment = current_alignment; + + current_alignment += geometry_msgs::msg::Pose::getCdrSerializedSize(data.pose(), current_alignment); - current_alignment += ((36) * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + if ((36) > 0) + { + current_alignment += ((36) * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + } + return current_alignment - initial_alignment; } @@ -120,15 +131,20 @@ size_t geometry_msgs::msg::PoseWithCovariance::getCdrSerializedSize( void geometry_msgs::msg::PoseWithCovariance::serialize( eprosima::fastcdr::Cdr& scdr) const { + scdr << m_pose; scdr << m_covariance; + + } void geometry_msgs::msg::PoseWithCovariance::deserialize( eprosima::fastcdr::Cdr& dcdr) { + dcdr >> m_pose; dcdr >> m_covariance; + } /*! @@ -173,7 +189,7 @@ geometry_msgs::msg::Pose& geometry_msgs::msg::PoseWithCovariance::pose() * @param _covariance New value to be copied in member covariance */ void geometry_msgs::msg::PoseWithCovariance::covariance( - const geometry_msgs::msg::geometry_msgs__PoseWithCovariance__double_array_36& _covariance) + const geometry_msgs::msg::double_pose_36& _covariance) { m_covariance = _covariance; } @@ -183,7 +199,7 @@ void geometry_msgs::msg::PoseWithCovariance::covariance( * @param _covariance New value to be moved in member covariance */ void geometry_msgs::msg::PoseWithCovariance::covariance( - geometry_msgs::msg::geometry_msgs__PoseWithCovariance__double_array_36&& _covariance) + geometry_msgs::msg::double_pose_36&& _covariance) { m_covariance = std::move(_covariance); } @@ -192,7 +208,7 @@ void geometry_msgs::msg::PoseWithCovariance::covariance( * @brief This function returns a constant reference to member covariance * @return Constant reference to member covariance */ -const geometry_msgs::msg::geometry_msgs__PoseWithCovariance__double_array_36& geometry_msgs::msg::PoseWithCovariance::covariance() const +const geometry_msgs::msg::double_pose_36& geometry_msgs::msg::PoseWithCovariance::covariance() const { return m_covariance; } @@ -201,17 +217,19 @@ const geometry_msgs::msg::geometry_msgs__PoseWithCovariance__double_array_36& ge * @brief This function returns a reference to member covariance * @return Reference to member covariance */ -geometry_msgs::msg::geometry_msgs__PoseWithCovariance__double_array_36& geometry_msgs::msg::PoseWithCovariance::covariance() +geometry_msgs::msg::double_pose_36& geometry_msgs::msg::PoseWithCovariance::covariance() { return m_covariance; } - size_t geometry_msgs::msg::PoseWithCovariance::getKeyMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return geometry_msgs_msg_PoseWithCovariance_max_key_cdr_typesize; + size_t current_align = current_alignment; + + + + return current_align; } bool geometry_msgs::msg::PoseWithCovariance::isKeyDefined() @@ -223,4 +241,7 @@ void geometry_msgs::msg::PoseWithCovariance::serializeKey( eprosima::fastcdr::Cdr& scdr) const { (void) scdr; + } + + diff --git a/LibCarla/source/carla/ros2/types/PoseWithCovariance.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariance.h similarity index 88% rename from LibCarla/source/carla/ros2/types/PoseWithCovariance.h rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariance.h index 25b061ded4f..dd98e464e18 100644 --- a/LibCarla/source/carla/ros2/types/PoseWithCovariance.h +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariance.h @@ -24,8 +24,6 @@ #include "Pose.h" -#include - #include #include #include @@ -66,7 +64,7 @@ class Cdr; namespace geometry_msgs { namespace msg { - typedef std::array geometry_msgs__PoseWithCovariance__double_array_36; + typedef std::array double_pose_36; /*! * @brief This class represents the structure PoseWithCovariance defined by the user in the IDL file. * @ingroup POSEWITHCOVARIANCE @@ -97,7 +95,7 @@ namespace geometry_msgs { * @param x Reference to the object geometry_msgs::msg::PoseWithCovariance that will be copied. */ eProsima_user_DllExport PoseWithCovariance( - PoseWithCovariance&& x) noexcept; + PoseWithCovariance&& x); /*! * @brief Copy assignment. @@ -111,7 +109,7 @@ namespace geometry_msgs { * @param x Reference to the object geometry_msgs::msg::PoseWithCovariance that will be copied. */ eProsima_user_DllExport PoseWithCovariance& operator =( - PoseWithCovariance&& x) noexcept; + PoseWithCovariance&& x); /*! * @brief Comparison operator. @@ -157,33 +155,33 @@ namespace geometry_msgs { * @param _covariance New value to be copied in member covariance */ eProsima_user_DllExport void covariance( - const geometry_msgs::msg::geometry_msgs__PoseWithCovariance__double_array_36& _covariance); + const geometry_msgs::msg::double_pose_36& _covariance); /*! * @brief This function moves the value in member covariance * @param _covariance New value to be moved in member covariance */ eProsima_user_DllExport void covariance( - geometry_msgs::msg::geometry_msgs__PoseWithCovariance__double_array_36&& _covariance); + geometry_msgs::msg::double_pose_36&& _covariance); /*! * @brief This function returns a constant reference to member covariance * @return Constant reference to member covariance */ - eProsima_user_DllExport const geometry_msgs::msg::geometry_msgs__PoseWithCovariance__double_array_36& covariance() const; + eProsima_user_DllExport const geometry_msgs::msg::double_pose_36& covariance() const; /*! * @brief This function returns a reference to member covariance * @return Reference to member covariance */ - eProsima_user_DllExport geometry_msgs::msg::geometry_msgs__PoseWithCovariance__double_array_36& covariance(); + eProsima_user_DllExport geometry_msgs::msg::double_pose_36& covariance(); /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -197,6 +195,7 @@ namespace geometry_msgs { const geometry_msgs::msg::PoseWithCovariance& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -211,6 +210,8 @@ namespace geometry_msgs { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -233,10 +234,11 @@ namespace geometry_msgs { eprosima::fastcdr::Cdr& cdr) const; private: + geometry_msgs::msg::Pose m_pose; - geometry_msgs::msg::geometry_msgs__PoseWithCovariance__double_array_36 m_covariance; + geometry_msgs::msg::double_pose_36 m_covariance; }; } // namespace msg } // namespace geometry_msgs -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCE_H_ +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/PoseWithCovariancePubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariancePubSubTypes.cxx similarity index 89% rename from LibCarla/source/carla/ros2/types/PoseWithCovariancePubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariancePubSubTypes.cxx index fe7a781d6a0..5757f76168d 100644 --- a/LibCarla/source/carla/ros2/types/PoseWithCovariancePubSubTypes.cpp +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariancePubSubTypes.cxx @@ -19,6 +19,7 @@ * This file was generated by the tool fastcdrgen. */ + #include #include @@ -84,21 +85,21 @@ namespace geometry_msgs { SerializedPayload_t* payload, void* data) { - try - { - //Convert DATA to pointer of your type - PoseWithCovariance* p_type = static_cast(data); + //Convert DATA to pointer of your type + PoseWithCovariance* p_type = static_cast(data); - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); - // Deserialize encapsulation. - deser.read_encapsulation(); - payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + try + { // Deserialize the object. p_type->deserialize(deser); } @@ -169,5 +170,8 @@ namespace geometry_msgs { } return true; } + + } //End of namespace msg + } //End of namespace geometry_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariancePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariancePubSubTypes.h new file mode 100644 index 00000000000..afe95d852f9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariancePubSubTypes.h @@ -0,0 +1,108 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PoseWithCovariancePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCE_PUBSUBTYPES_H_ + +#include +#include + +#include "PoseWithCovariance.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated PoseWithCovariance is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace geometry_msgs +{ + namespace msg + { + typedef std::array double_pose_36; + /*! + * @brief This class represents the TopicDataType of the type PoseWithCovariance defined by the user in the IDL file. + * @ingroup POSEWITHCOVARIANCE + */ + class PoseWithCovariancePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef PoseWithCovariance type; + + eProsima_user_DllExport PoseWithCovariancePubSubType(); + + eProsima_user_DllExport virtual ~PoseWithCovariancePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) PoseWithCovariance(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/Quaternion.cpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Quaternion.cxx similarity index 85% rename from LibCarla/source/carla/ros2/types/Quaternion.cpp rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Quaternion.cxx index 4858a84b251..8146a4ad617 100644 --- a/LibCarla/source/carla/ros2/types/Quaternion.cpp +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Quaternion.cxx @@ -34,23 +34,24 @@ using namespace eprosima::fastcdr::exception; #include -#define geometry_msgs_msg_Quaternion_max_cdr_typesize 32ULL; -#define geometry_msgs_msg_Quaternion_max_key_cdr_typesize 0ULL; - geometry_msgs::msg::Quaternion::Quaternion() { - // double m_x + // m_x com.eprosima.idl.parser.typecode.PrimitiveTypeCode@593aaf41 m_x = 0.0; - // double m_y + // m_y com.eprosima.idl.parser.typecode.PrimitiveTypeCode@5a56cdac m_y = 0.0; - // double m_z + // m_z com.eprosima.idl.parser.typecode.PrimitiveTypeCode@7c711375 m_z = 0.0; - // double m_w + // m_w com.eprosima.idl.parser.typecode.PrimitiveTypeCode@57cf54e1 m_w = 1.0; + } geometry_msgs::msg::Quaternion::~Quaternion() { + + + } geometry_msgs::msg::Quaternion::Quaternion( @@ -63,7 +64,7 @@ geometry_msgs::msg::Quaternion::Quaternion( } geometry_msgs::msg::Quaternion::Quaternion( - Quaternion&& x) noexcept + Quaternion&& x) { m_x = x.m_x; m_y = x.m_y; @@ -74,6 +75,7 @@ geometry_msgs::msg::Quaternion::Quaternion( geometry_msgs::msg::Quaternion& geometry_msgs::msg::Quaternion::operator =( const Quaternion& x) { + m_x = x.m_x; m_y = x.m_y; m_z = x.m_z; @@ -83,8 +85,9 @@ geometry_msgs::msg::Quaternion& geometry_msgs::msg::Quaternion::operator =( } geometry_msgs::msg::Quaternion& geometry_msgs::msg::Quaternion::operator =( - Quaternion&& x) noexcept + Quaternion&& x) { + m_x = x.m_x; m_y = x.m_y; m_z = x.m_z; @@ -96,6 +99,7 @@ geometry_msgs::msg::Quaternion& geometry_msgs::msg::Quaternion::operator =( bool geometry_msgs::msg::Quaternion::operator ==( const Quaternion& x) const { + return (m_x == x.m_x && m_y == x.m_y && m_z == x.m_z && m_w == x.m_w); } @@ -108,8 +112,23 @@ bool geometry_msgs::msg::Quaternion::operator !=( size_t geometry_msgs::msg::Quaternion::getMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return geometry_msgs_msg_Quaternion_max_cdr_typesize; + size_t initial_alignment = current_alignment; + + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + + return current_alignment - initial_alignment; } size_t geometry_msgs::msg::Quaternion::getCdrSerializedSize( @@ -118,26 +137,39 @@ size_t geometry_msgs::msg::Quaternion::getCdrSerializedSize( { (void)data; size_t initial_alignment = current_alignment; + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + return current_alignment - initial_alignment; } void geometry_msgs::msg::Quaternion::serialize( eprosima::fastcdr::Cdr& scdr) const { + scdr << m_x; scdr << m_y; scdr << m_z; scdr << m_w; + } void geometry_msgs::msg::Quaternion::deserialize( eprosima::fastcdr::Cdr& dcdr) { + dcdr >> m_x; dcdr >> m_y; dcdr >> m_z; @@ -256,11 +288,15 @@ double& geometry_msgs::msg::Quaternion::w() return m_w; } + size_t geometry_msgs::msg::Quaternion::getKeyMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return geometry_msgs_msg_Quaternion_max_key_cdr_typesize; + size_t current_align = current_alignment; + + + + return current_align; } bool geometry_msgs::msg::Quaternion::isKeyDefined() @@ -272,4 +308,7 @@ void geometry_msgs::msg::Quaternion::serializeKey( eprosima::fastcdr::Cdr& scdr) const { (void) scdr; + } + + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Quaternion.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Quaternion.h new file mode 100644 index 00000000000..bc793f05b18 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Quaternion.h @@ -0,0 +1,270 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Quaternion.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNION_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNION_H_ + + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(Quaternion_SOURCE) +#define Quaternion_DllAPI __declspec( dllexport ) +#else +#define Quaternion_DllAPI __declspec( dllimport ) +#endif // Quaternion_SOURCE +#else +#define Quaternion_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define Quaternion_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace geometry_msgs { + namespace msg { + /*! + * @brief This class represents the structure Quaternion defined by the user in the IDL file. + * @ingroup QUATERNION + */ + class Quaternion + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Quaternion(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Quaternion(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object geometry_msgs::msg::Quaternion that will be copied. + */ + eProsima_user_DllExport Quaternion( + const Quaternion& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object geometry_msgs::msg::Quaternion that will be copied. + */ + eProsima_user_DllExport Quaternion( + Quaternion&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object geometry_msgs::msg::Quaternion that will be copied. + */ + eProsima_user_DllExport Quaternion& operator =( + const Quaternion& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object geometry_msgs::msg::Quaternion that will be copied. + */ + eProsima_user_DllExport Quaternion& operator =( + Quaternion&& x); + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::Quaternion object to compare. + */ + eProsima_user_DllExport bool operator ==( + const Quaternion& x) const; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::Quaternion object to compare. + */ + eProsima_user_DllExport bool operator !=( + const Quaternion& x) const; + + /*! + * @brief This function sets a value in member x + * @param _x New value for member x + */ + eProsima_user_DllExport void x( + double _x); + + /*! + * @brief This function returns the value of member x + * @return Value of member x + */ + eProsima_user_DllExport double x() const; + + /*! + * @brief This function returns a reference to member x + * @return Reference to member x + */ + eProsima_user_DllExport double& x(); + + /*! + * @brief This function sets a value in member y + * @param _y New value for member y + */ + eProsima_user_DllExport void y( + double _y); + + /*! + * @brief This function returns the value of member y + * @return Value of member y + */ + eProsima_user_DllExport double y() const; + + /*! + * @brief This function returns a reference to member y + * @return Reference to member y + */ + eProsima_user_DllExport double& y(); + + /*! + * @brief This function sets a value in member z + * @param _z New value for member z + */ + eProsima_user_DllExport void z( + double _z); + + /*! + * @brief This function returns the value of member z + * @return Value of member z + */ + eProsima_user_DllExport double z() const; + + /*! + * @brief This function returns a reference to member z + * @return Reference to member z + */ + eProsima_user_DllExport double& z(); + + /*! + * @brief This function sets a value in member w + * @param _w New value for member w + */ + eProsima_user_DllExport void w( + double _w); + + /*! + * @brief This function returns the value of member w + * @return Value of member w + */ + eProsima_user_DllExport double w() const; + + /*! + * @brief This function returns a reference to member w + * @return Reference to member w + */ + eProsima_user_DllExport double& w(); + + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const geometry_msgs::msg::Quaternion& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + double m_x; + double m_y; + double m_z; + double m_w; + }; + } // namespace msg +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNION_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/QuaternionPubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/QuaternionPubSubTypes.cxx similarity index 89% rename from LibCarla/source/carla/ros2/types/QuaternionPubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/QuaternionPubSubTypes.cxx index 8b4581a39a8..f3f6fc8873a 100644 --- a/LibCarla/source/carla/ros2/types/QuaternionPubSubTypes.cpp +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/QuaternionPubSubTypes.cxx @@ -19,6 +19,7 @@ * This file was generated by the tool fastcdrgen. */ + #include #include @@ -83,21 +84,21 @@ namespace geometry_msgs { SerializedPayload_t* payload, void* data) { - try - { - //Convert DATA to pointer of your type - Quaternion* p_type = static_cast(data); + //Convert DATA to pointer of your type + Quaternion* p_type = static_cast(data); - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); - // Deserialize encapsulation. - deser.read_encapsulation(); - payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + try + { // Deserialize the object. p_type->deserialize(deser); } @@ -168,5 +169,8 @@ namespace geometry_msgs { } return true; } + + } //End of namespace msg + } //End of namespace geometry_msgs diff --git a/LibCarla/source/carla/ros2/types/QuaternionPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/QuaternionPubSubTypes.h similarity index 76% rename from LibCarla/source/carla/ros2/types/QuaternionPubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/QuaternionPubSubTypes.h index 17057b049d2..df71e2249c9 100644 --- a/LibCarla/source/carla/ros2/types/QuaternionPubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/QuaternionPubSubTypes.h @@ -19,6 +19,7 @@ * This file was generated by the tool fastcdrgen. */ + #ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNION_PUBSUBTYPES_H_ #define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNION_PUBSUBTYPES_H_ @@ -36,36 +37,6 @@ namespace geometry_msgs { namespace msg { - - #ifndef SWIG - namespace detail { - - template - struct Quaternion_rob - { - friend constexpr typename Tag::type get( - Tag) - { - return M; - } - }; - - struct Quaternion_f - { - typedef double Quaternion::* type; - friend constexpr type get( - Quaternion_f); - }; - - template struct Quaternion_rob; - - template - inline size_t constexpr Quaternion_offset_of() { - return ((::size_t) &reinterpret_cast((((T*)0)->*get(Tag())))); - } - } - #endif - /*! * @brief This class represents the TopicDataType of the type Quaternion defined by the user in the IDL file. * @ingroup QUATERNION @@ -78,7 +49,7 @@ namespace geometry_msgs eProsima_user_DllExport QuaternionPubSubType(); - eProsima_user_DllExport virtual ~QuaternionPubSubType() override; + eProsima_user_DllExport virtual ~QuaternionPubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -112,7 +83,7 @@ namespace geometry_msgs #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN eProsima_user_DllExport inline bool is_plain() const override { - return is_plain_impl(); + return true; } #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN @@ -126,15 +97,11 @@ namespace geometry_msgs } #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; unsigned char* m_keyBuffer; - private: - static constexpr bool is_plain_impl() - { - return 32ULL == (detail::Quaternion_offset_of() + sizeof(double)); - - }}; + }; } } -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNION_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNION_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/Transform.cpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Transform.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/Transform.cpp rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Transform.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Transform.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Transform.h new file mode 100644 index 00000000000..2d84f30f040 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Transform.h @@ -0,0 +1,223 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Transform.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORM_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORM_H_ + +#include "Quaternion.h" +#include "Vector3.h" + +#include + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(Transform_SOURCE) +#define Transform_DllAPI __declspec(dllexport) +#else +#define Transform_DllAPI __declspec(dllimport) +#endif // Transform_SOURCE +#else +#define Transform_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define Transform_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace geometry_msgs { +namespace msg { +/*! + * @brief This class represents the structure Transform defined by the user in the IDL file. + * @ingroup TRANSFORM + */ +class Transform { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Transform(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Transform(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object geometry_msgs::msg::Transform that will be copied. + */ + eProsima_user_DllExport Transform(const Transform& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object geometry_msgs::msg::Transform that will be copied. + */ + eProsima_user_DllExport Transform(Transform&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object geometry_msgs::msg::Transform that will be copied. + */ + eProsima_user_DllExport Transform& operator=(const Transform& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object geometry_msgs::msg::Transform that will be copied. + */ + eProsima_user_DllExport Transform& operator=(Transform&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::Transform object to compare. + */ + eProsima_user_DllExport bool operator==(const Transform& x) const; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::Transform object to compare. + */ + eProsima_user_DllExport bool operator!=(const Transform& x) const; + + /*! + * @brief This function copies the value in member translation + * @param _translation New value to be copied in member translation + */ + eProsima_user_DllExport void translation(const geometry_msgs::msg::Vector3& _translation); + + /*! + * @brief This function moves the value in member translation + * @param _translation New value to be moved in member translation + */ + eProsima_user_DllExport void translation(geometry_msgs::msg::Vector3&& _translation); + + /*! + * @brief This function returns a constant reference to member translation + * @return Constant reference to member translation + */ + eProsima_user_DllExport const geometry_msgs::msg::Vector3& translation() const; + + /*! + * @brief This function returns a reference to member translation + * @return Reference to member translation + */ + eProsima_user_DllExport geometry_msgs::msg::Vector3& translation(); + /*! + * @brief This function copies the value in member rotation + * @param _rotation New value to be copied in member rotation + */ + eProsima_user_DllExport void rotation(const geometry_msgs::msg::Quaternion& _rotation); + + /*! + * @brief This function moves the value in member rotation + * @param _rotation New value to be moved in member rotation + */ + eProsima_user_DllExport void rotation(geometry_msgs::msg::Quaternion&& _rotation); + + /*! + * @brief This function returns a constant reference to member rotation + * @return Constant reference to member rotation + */ + eProsima_user_DllExport const geometry_msgs::msg::Quaternion& rotation() const; + + /*! + * @brief This function returns a reference to member rotation + * @return Reference to member rotation + */ + eProsima_user_DllExport geometry_msgs::msg::Quaternion& rotation(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const geometry_msgs::msg::Transform& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + geometry_msgs::msg::Vector3 m_translation; + geometry_msgs::msg::Quaternion m_rotation; +}; +} // namespace msg +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORM_H_ diff --git a/LibCarla/source/carla/ros2/types/TransformPubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformPubSubTypes.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/TransformPubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformPubSubTypes.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformPubSubTypes.h new file mode 100644 index 00000000000..6f463271b55 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformPubSubTypes.h @@ -0,0 +1,124 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file TransformPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORM_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORM_PUBSUBTYPES_H_ + +#include +#include + +#include "Transform.h" + +#include "QuaternionPubSubTypes.h" +#include "Vector3PubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated Transform is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace geometry_msgs { +namespace msg { + +#ifndef SWIG +namespace detail { + +template +struct Transform_rob { + friend constexpr typename Tag::type get(Tag) { + return M; + } +}; + +struct Transform_f { + typedef geometry_msgs::msg::Quaternion Transform::*type; + friend constexpr type get(Transform_f); +}; + +template struct Transform_rob; + +template +inline size_t constexpr Transform_offset_of() { + return ((::size_t) & reinterpret_cast((((T*)0)->*get(Tag())))); +} +} // namespace detail +#endif + +/*! + * @brief This class represents the TopicDataType of the type Transform defined by the user in the IDL file. + * @ingroup TRANSFORM + */ +class TransformPubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef Transform type; + + eProsima_user_DllExport TransformPubSubType(); + + eProsima_user_DllExport virtual ~TransformPubSubType() override; + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return true; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return is_plain_impl(); + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + new (memory) Transform(); + return true; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; + unsigned char* m_keyBuffer; + +private: + static constexpr bool is_plain_impl() { + return 56ULL == + (detail::Transform_offset_of() + sizeof(geometry_msgs::msg::Quaternion)); + } +}; +} // namespace msg +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORM_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/TransformStamped.cpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStamped.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/TransformStamped.cpp rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStamped.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStamped.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStamped.h new file mode 100644 index 00000000000..07821eb4179 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStamped.h @@ -0,0 +1,247 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file TransformStamped.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPED_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPED_H_ + +#include "Transform.h" +#include "std_msgs/msg/Header.h" + +#include + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(TransformStamped_SOURCE) +#define TransformStamped_DllAPI __declspec(dllexport) +#else +#define TransformStamped_DllAPI __declspec(dllimport) +#endif // TransformStamped_SOURCE +#else +#define TransformStamped_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define TransformStamped_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace geometry_msgs { +namespace msg { +/*! + * @brief This class represents the structure TransformStamped defined by the user in the IDL file. + * @ingroup TRANSFORMSTAMPED + */ +class TransformStamped { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport TransformStamped(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~TransformStamped(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object geometry_msgs::msg::TransformStamped that will be copied. + */ + eProsima_user_DllExport TransformStamped(const TransformStamped& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object geometry_msgs::msg::TransformStamped that will be copied. + */ + eProsima_user_DllExport TransformStamped(TransformStamped&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object geometry_msgs::msg::TransformStamped that will be copied. + */ + eProsima_user_DllExport TransformStamped& operator=(const TransformStamped& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object geometry_msgs::msg::TransformStamped that will be copied. + */ + eProsima_user_DllExport TransformStamped& operator=(TransformStamped&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::TransformStamped object to compare. + */ + eProsima_user_DllExport bool operator==(const TransformStamped& x) const; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::TransformStamped object to compare. + */ + eProsima_user_DllExport bool operator!=(const TransformStamped& x) const; + + /*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ + eProsima_user_DllExport void header(const std_msgs::msg::Header& _header); + + /*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ + eProsima_user_DllExport void header(std_msgs::msg::Header&& _header); + + /*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ + eProsima_user_DllExport const std_msgs::msg::Header& header() const; + + /*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ + eProsima_user_DllExport std_msgs::msg::Header& header(); + /*! + * @brief This function copies the value in member child_frame_id + * @param _child_frame_id New value to be copied in member child_frame_id + */ + eProsima_user_DllExport void child_frame_id(const std::string& _child_frame_id); + + /*! + * @brief This function moves the value in member child_frame_id + * @param _child_frame_id New value to be moved in member child_frame_id + */ + eProsima_user_DllExport void child_frame_id(std::string&& _child_frame_id); + + /*! + * @brief This function returns a constant reference to member child_frame_id + * @return Constant reference to member child_frame_id + */ + eProsima_user_DllExport const std::string& child_frame_id() const; + + /*! + * @brief This function returns a reference to member child_frame_id + * @return Reference to member child_frame_id + */ + eProsima_user_DllExport std::string& child_frame_id(); + /*! + * @brief This function copies the value in member transform + * @param _transform New value to be copied in member transform + */ + eProsima_user_DllExport void transform(const geometry_msgs::msg::Transform& _transform); + + /*! + * @brief This function moves the value in member transform + * @param _transform New value to be moved in member transform + */ + eProsima_user_DllExport void transform(geometry_msgs::msg::Transform&& _transform); + + /*! + * @brief This function returns a constant reference to member transform + * @return Constant reference to member transform + */ + eProsima_user_DllExport const geometry_msgs::msg::Transform& transform() const; + + /*! + * @brief This function returns a reference to member transform + * @return Reference to member transform + */ + eProsima_user_DllExport geometry_msgs::msg::Transform& transform(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const geometry_msgs::msg::TransformStamped& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + std_msgs::msg::Header m_header; + std::string m_child_frame_id; + geometry_msgs::msg::Transform m_transform; +}; +} // namespace msg +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPED_H_ diff --git a/LibCarla/source/carla/ros2/types/TransformStampedPubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStampedPubSubTypes.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/TransformStampedPubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStampedPubSubTypes.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStampedPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStampedPubSubTypes.h new file mode 100644 index 00000000000..c8fcaba9ce3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStampedPubSubTypes.h @@ -0,0 +1,95 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file TransformStampedPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPED_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPED_PUBSUBTYPES_H_ + +#include +#include + +#include "TransformStamped.h" + +#include "TransformPubSubTypes.h" +#include "std_msgs/msg/HeaderPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated TransformStamped is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace geometry_msgs { +namespace msg { + +/*! + * @brief This class represents the TopicDataType of the type TransformStamped defined by the user in the IDL file. + * @ingroup TRANSFORMSTAMPED + */ +class TransformStampedPubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef TransformStamped type; + + eProsima_user_DllExport TransformStampedPubSubType(); + + eProsima_user_DllExport virtual ~TransformStampedPubSubType() override; + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + (void)memory; + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; + unsigned char* m_keyBuffer; +}; +} // namespace msg +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPED_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/Twist.cpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Twist.cxx similarity index 89% rename from LibCarla/source/carla/ros2/types/Twist.cpp rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Twist.cxx index 553921f89c8..1e4ea4150d7 100644 --- a/LibCarla/source/carla/ros2/types/Twist.cpp +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Twist.cxx @@ -34,17 +34,18 @@ using namespace eprosima::fastcdr::exception; #include -#define geometry_msgs_msg_Vector3_max_cdr_typesize 24ULL; -#define geometry_msgs_msg_Twist_max_cdr_typesize 48ULL; -#define geometry_msgs_msg_Vector3_max_key_cdr_typesize 0ULL; -#define geometry_msgs_msg_Twist_max_key_cdr_typesize 0ULL; - geometry_msgs::msg::Twist::Twist() { + // m_linear com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@2b48a640 + + // m_angular com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@2b48a640 + + } geometry_msgs::msg::Twist::~Twist() { + } geometry_msgs::msg::Twist::Twist( @@ -55,7 +56,7 @@ geometry_msgs::msg::Twist::Twist( } geometry_msgs::msg::Twist::Twist( - Twist&& x) noexcept + Twist&& x) { m_linear = std::move(x.m_linear); m_angular = std::move(x.m_angular); @@ -64,6 +65,7 @@ geometry_msgs::msg::Twist::Twist( geometry_msgs::msg::Twist& geometry_msgs::msg::Twist::operator =( const Twist& x) { + m_linear = x.m_linear; m_angular = x.m_angular; @@ -71,8 +73,9 @@ geometry_msgs::msg::Twist& geometry_msgs::msg::Twist::operator =( } geometry_msgs::msg::Twist& geometry_msgs::msg::Twist::operator =( - Twist&& x) noexcept + Twist&& x) { + m_linear = std::move(x.m_linear); m_angular = std::move(x.m_angular); @@ -82,6 +85,7 @@ geometry_msgs::msg::Twist& geometry_msgs::msg::Twist::operator =( bool geometry_msgs::msg::Twist::operator ==( const Twist& x) const { + return (m_linear == x.m_linear && m_angular == x.m_angular); } @@ -94,15 +98,23 @@ bool geometry_msgs::msg::Twist::operator !=( size_t geometry_msgs::msg::Twist::getMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return geometry_msgs_msg_Twist_max_cdr_typesize; + size_t initial_alignment = current_alignment; + + + current_alignment += geometry_msgs::msg::Vector3::getMaxCdrSerializedSize(current_alignment); + current_alignment += geometry_msgs::msg::Vector3::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; } size_t geometry_msgs::msg::Twist::getCdrSerializedSize( const geometry_msgs::msg::Twist& data, size_t current_alignment) { + (void)data; size_t initial_alignment = current_alignment; + + current_alignment += geometry_msgs::msg::Vector3::getCdrSerializedSize(data.linear(), current_alignment); current_alignment += geometry_msgs::msg::Vector3::getCdrSerializedSize(data.angular(), current_alignment); @@ -112,13 +124,16 @@ size_t geometry_msgs::msg::Twist::getCdrSerializedSize( void geometry_msgs::msg::Twist::serialize( eprosima::fastcdr::Cdr& scdr) const { + scdr << m_linear; scdr << m_angular; + } void geometry_msgs::msg::Twist::deserialize( eprosima::fastcdr::Cdr& dcdr) { + dcdr >> m_linear; dcdr >> m_angular; } @@ -160,7 +175,6 @@ geometry_msgs::msg::Vector3& geometry_msgs::msg::Twist::linear() { return m_linear; } - /*! * @brief This function copies the value in member angular * @param _angular New value to be copied in member angular @@ -199,12 +213,14 @@ geometry_msgs::msg::Vector3& geometry_msgs::msg::Twist::angular() return m_angular; } - size_t geometry_msgs::msg::Twist::getKeyMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return geometry_msgs_msg_Twist_max_key_cdr_typesize; + size_t current_align = current_alignment; + + + + return current_align; } bool geometry_msgs::msg::Twist::isKeyDefined() @@ -216,4 +232,7 @@ void geometry_msgs::msg::Twist::serializeKey( eprosima::fastcdr::Cdr& scdr) const { (void) scdr; + } + + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Twist.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Twist.h new file mode 100644 index 00000000000..48cca0f1b1f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Twist.h @@ -0,0 +1,243 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Twist.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWIST_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWIST_H_ + +#include "Vector3.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec( dllexport ) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(Twist_SOURCE) +#define Twist_DllAPI __declspec( dllexport ) +#else +#define Twist_DllAPI __declspec( dllimport ) +#endif // Twist_SOURCE +#else +#define Twist_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define Twist_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + + +namespace geometry_msgs { + namespace msg { + /*! + * @brief This class represents the structure Twist defined by the user in the IDL file. + * @ingroup TWIST + */ + class Twist + { + public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Twist(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Twist(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object geometry_msgs::msg::Twist that will be copied. + */ + eProsima_user_DllExport Twist( + const Twist& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object geometry_msgs::msg::Twist that will be copied. + */ + eProsima_user_DllExport Twist( + Twist&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object geometry_msgs::msg::Twist that will be copied. + */ + eProsima_user_DllExport Twist& operator =( + const Twist& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object geometry_msgs::msg::Twist that will be copied. + */ + eProsima_user_DllExport Twist& operator =( + Twist&& x); + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::Twist object to compare. + */ + eProsima_user_DllExport bool operator ==( + const Twist& x) const; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::Twist object to compare. + */ + eProsima_user_DllExport bool operator !=( + const Twist& x) const; + + /*! + * @brief This function copies the value in member linear + * @param _linear New value to be copied in member linear + */ + eProsima_user_DllExport void linear( + const geometry_msgs::msg::Vector3& _linear); + + /*! + * @brief This function moves the value in member linear + * @param _linear New value to be moved in member linear + */ + eProsima_user_DllExport void linear( + geometry_msgs::msg::Vector3&& _linear); + + /*! + * @brief This function returns a constant reference to member linear + * @return Constant reference to member linear + */ + eProsima_user_DllExport const geometry_msgs::msg::Vector3& linear() const; + + /*! + * @brief This function returns a reference to member linear + * @return Reference to member linear + */ + eProsima_user_DllExport geometry_msgs::msg::Vector3& linear(); + /*! + * @brief This function copies the value in member angular + * @param _angular New value to be copied in member angular + */ + eProsima_user_DllExport void angular( + const geometry_msgs::msg::Vector3& _angular); + + /*! + * @brief This function moves the value in member angular + * @param _angular New value to be moved in member angular + */ + eProsima_user_DllExport void angular( + geometry_msgs::msg::Vector3&& _angular); + + /*! + * @brief This function returns a constant reference to member angular + * @return Constant reference to member angular + */ + eProsima_user_DllExport const geometry_msgs::msg::Vector3& angular() const; + + /*! + * @brief This function returns a reference to member angular + * @return Reference to member angular + */ + eProsima_user_DllExport geometry_msgs::msg::Vector3& angular(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize( + const geometry_msgs::msg::Twist& data, + size_t current_alignment = 0); + + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr); + + + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey( + eprosima::fastcdr::Cdr& cdr) const; + + private: + + geometry_msgs::msg::Vector3 m_linear; + geometry_msgs::msg::Vector3 m_angular; + }; + } // namespace msg +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWIST_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/TwistPubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistPubSubTypes.cxx similarity index 89% rename from LibCarla/source/carla/ros2/types/TwistPubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistPubSubTypes.cxx index 5cabda52668..853ad47461f 100644 --- a/LibCarla/source/carla/ros2/types/TwistPubSubTypes.cpp +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistPubSubTypes.cxx @@ -19,6 +19,7 @@ * This file was generated by the tool fastcdrgen. */ + #include #include @@ -83,21 +84,21 @@ namespace geometry_msgs { SerializedPayload_t* payload, void* data) { - try - { - //Convert DATA to pointer of your type - Twist* p_type = static_cast(data); + //Convert DATA to pointer of your type + Twist* p_type = static_cast(data); - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); - // Deserialize encapsulation. - deser.read_encapsulation(); - payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + try + { // Deserialize the object. p_type->deserialize(deser); } @@ -168,5 +169,8 @@ namespace geometry_msgs { } return true; } + + } //End of namespace msg + } //End of namespace geometry_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistPubSubTypes.h new file mode 100644 index 00000000000..4a8a641bb88 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistPubSubTypes.h @@ -0,0 +1,107 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file TwistPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWIST_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWIST_PUBSUBTYPES_H_ + +#include +#include + +#include "Twist.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated Twist is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace geometry_msgs +{ + namespace msg + { + /*! + * @brief This class represents the TopicDataType of the type Twist defined by the user in the IDL file. + * @ingroup TWIST + */ + class TwistPubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef Twist type; + + eProsima_user_DllExport TwistPubSubType(); + + eProsima_user_DllExport virtual ~TwistPubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) Twist(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWIST_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/TwistWithCovariance.cpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariance.cxx similarity index 80% rename from LibCarla/source/carla/ros2/types/TwistWithCovariance.cpp rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariance.cxx index 332f228efba..ce9eb6c2531 100644 --- a/LibCarla/source/carla/ros2/types/TwistWithCovariance.cpp +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariance.cxx @@ -34,23 +34,19 @@ using namespace eprosima::fastcdr::exception; #include -#define geometry_msgs_msg_TwistWithCovariance_max_cdr_typesize 336ULL; -#define geometry_msgs_msg_Vector3_max_cdr_typesize 24ULL; -#define geometry_msgs_msg_Twist_max_cdr_typesize 48ULL; -#define geometry_msgs_msg_TwistWithCovariance_max_key_cdr_typesize 0ULL; -#define geometry_msgs_msg_Vector3_max_key_cdr_typesize 0ULL; -#define geometry_msgs_msg_Twist_max_key_cdr_typesize 0ULL; geometry_msgs::msg::TwistWithCovariance::TwistWithCovariance() { - // geometry_msgs::msg::Twist m_twist + // m_twist com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@10163d6 - // geometry_msgs::msg::geometry_msgs__TwistWithCovariance__double_array_36 m_covariance + // m_covariance com.eprosima.idl.parser.typecode.AliasTypeCode@2dde1bff memset(&m_covariance, 0, (36) * 8); + } geometry_msgs::msg::TwistWithCovariance::~TwistWithCovariance() { + } geometry_msgs::msg::TwistWithCovariance::TwistWithCovariance( @@ -61,7 +57,7 @@ geometry_msgs::msg::TwistWithCovariance::TwistWithCovariance( } geometry_msgs::msg::TwistWithCovariance::TwistWithCovariance( - TwistWithCovariance&& x) noexcept + TwistWithCovariance&& x) { m_twist = std::move(x.m_twist); m_covariance = std::move(x.m_covariance); @@ -70,6 +66,7 @@ geometry_msgs::msg::TwistWithCovariance::TwistWithCovariance( geometry_msgs::msg::TwistWithCovariance& geometry_msgs::msg::TwistWithCovariance::operator =( const TwistWithCovariance& x) { + m_twist = x.m_twist; m_covariance = x.m_covariance; @@ -77,8 +74,9 @@ geometry_msgs::msg::TwistWithCovariance& geometry_msgs::msg::TwistWithCovariance } geometry_msgs::msg::TwistWithCovariance& geometry_msgs::msg::TwistWithCovariance::operator =( - TwistWithCovariance&& x) noexcept + TwistWithCovariance&& x) { + m_twist = std::move(x.m_twist); m_covariance = std::move(x.m_covariance); @@ -88,6 +86,7 @@ geometry_msgs::msg::TwistWithCovariance& geometry_msgs::msg::TwistWithCovariance bool geometry_msgs::msg::TwistWithCovariance::operator ==( const TwistWithCovariance& x) const { + return (m_twist == x.m_twist && m_covariance == x.m_covariance); } @@ -100,17 +99,31 @@ bool geometry_msgs::msg::TwistWithCovariance::operator !=( size_t geometry_msgs::msg::TwistWithCovariance::getMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return geometry_msgs_msg_TwistWithCovariance_max_cdr_typesize; + size_t initial_alignment = current_alignment; + + + current_alignment += geometry_msgs::msg::Twist::getMaxCdrSerializedSize(current_alignment); + current_alignment += ((36) * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + + return current_alignment - initial_alignment; } size_t geometry_msgs::msg::TwistWithCovariance::getCdrSerializedSize( const geometry_msgs::msg::TwistWithCovariance& data, size_t current_alignment) { + (void)data; size_t initial_alignment = current_alignment; + + current_alignment += geometry_msgs::msg::Twist::getCdrSerializedSize(data.twist(), current_alignment); - current_alignment += ((36) * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + if ((36) > 0) + { + current_alignment += ((36) * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + } + return current_alignment - initial_alignment; } @@ -118,15 +131,20 @@ size_t geometry_msgs::msg::TwistWithCovariance::getCdrSerializedSize( void geometry_msgs::msg::TwistWithCovariance::serialize( eprosima::fastcdr::Cdr& scdr) const { + scdr << m_twist; scdr << m_covariance; + + } void geometry_msgs::msg::TwistWithCovariance::deserialize( eprosima::fastcdr::Cdr& dcdr) { + dcdr >> m_twist; dcdr >> m_covariance; + } /*! @@ -166,13 +184,12 @@ geometry_msgs::msg::Twist& geometry_msgs::msg::TwistWithCovariance::twist() { return m_twist; } - /*! * @brief This function copies the value in member covariance * @param _covariance New value to be copied in member covariance */ void geometry_msgs::msg::TwistWithCovariance::covariance( - const geometry_msgs::msg::geometry_msgs__TwistWithCovariance__double_array_36& _covariance) + const geometry_msgs::msg::double_twist_36& _covariance) { m_covariance = _covariance; } @@ -182,7 +199,7 @@ void geometry_msgs::msg::TwistWithCovariance::covariance( * @param _covariance New value to be moved in member covariance */ void geometry_msgs::msg::TwistWithCovariance::covariance( - geometry_msgs::msg::geometry_msgs__TwistWithCovariance__double_array_36&& _covariance) + geometry_msgs::msg::double_twist_36&& _covariance) { m_covariance = std::move(_covariance); } @@ -191,7 +208,7 @@ void geometry_msgs::msg::TwistWithCovariance::covariance( * @brief This function returns a constant reference to member covariance * @return Constant reference to member covariance */ -const geometry_msgs::msg::geometry_msgs__TwistWithCovariance__double_array_36& geometry_msgs::msg::TwistWithCovariance::covariance() const +const geometry_msgs::msg::double_twist_36& geometry_msgs::msg::TwistWithCovariance::covariance() const { return m_covariance; } @@ -200,7 +217,7 @@ const geometry_msgs::msg::geometry_msgs__TwistWithCovariance__double_array_36& g * @brief This function returns a reference to member covariance * @return Reference to member covariance */ -geometry_msgs::msg::geometry_msgs__TwistWithCovariance__double_array_36& geometry_msgs::msg::TwistWithCovariance::covariance() +geometry_msgs::msg::double_twist_36& geometry_msgs::msg::TwistWithCovariance::covariance() { return m_covariance; } @@ -208,8 +225,11 @@ geometry_msgs::msg::geometry_msgs__TwistWithCovariance__double_array_36& geometr size_t geometry_msgs::msg::TwistWithCovariance::getKeyMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return geometry_msgs_msg_TwistWithCovariance_max_key_cdr_typesize; + size_t current_align = current_alignment; + + + + return current_align; } bool geometry_msgs::msg::TwistWithCovariance::isKeyDefined() @@ -221,4 +241,7 @@ void geometry_msgs::msg::TwistWithCovariance::serializeKey( eprosima::fastcdr::Cdr& scdr) const { (void) scdr; + } + + diff --git a/LibCarla/source/carla/ros2/types/TwistWithCovariance.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariance.h similarity index 88% rename from LibCarla/source/carla/ros2/types/TwistWithCovariance.h rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariance.h index 4aa2477567d..40c89bab4fd 100644 --- a/LibCarla/source/carla/ros2/types/TwistWithCovariance.h +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariance.h @@ -24,8 +24,6 @@ #include "Twist.h" -#include - #include #include #include @@ -66,7 +64,7 @@ class Cdr; namespace geometry_msgs { namespace msg { - typedef std::array geometry_msgs__TwistWithCovariance__double_array_36; + typedef std::array double_twist_36; /*! * @brief This class represents the structure TwistWithCovariance defined by the user in the IDL file. * @ingroup TWISTWITHCOVARIANCE @@ -97,7 +95,7 @@ namespace geometry_msgs { * @param x Reference to the object geometry_msgs::msg::TwistWithCovariance that will be copied. */ eProsima_user_DllExport TwistWithCovariance( - TwistWithCovariance&& x) noexcept; + TwistWithCovariance&& x); /*! * @brief Copy assignment. @@ -111,7 +109,7 @@ namespace geometry_msgs { * @param x Reference to the object geometry_msgs::msg::TwistWithCovariance that will be copied. */ eProsima_user_DllExport TwistWithCovariance& operator =( - TwistWithCovariance&& x) noexcept; + TwistWithCovariance&& x); /*! * @brief Comparison operator. @@ -157,33 +155,33 @@ namespace geometry_msgs { * @param _covariance New value to be copied in member covariance */ eProsima_user_DllExport void covariance( - const geometry_msgs::msg::geometry_msgs__TwistWithCovariance__double_array_36& _covariance); + const geometry_msgs::msg::double_twist_36& _covariance); /*! * @brief This function moves the value in member covariance * @param _covariance New value to be moved in member covariance */ eProsima_user_DllExport void covariance( - geometry_msgs::msg::geometry_msgs__TwistWithCovariance__double_array_36&& _covariance); + geometry_msgs::msg::double_twist_36&& _covariance); /*! * @brief This function returns a constant reference to member covariance * @return Constant reference to member covariance */ - eProsima_user_DllExport const geometry_msgs::msg::geometry_msgs__TwistWithCovariance__double_array_36& covariance() const; + eProsima_user_DllExport const geometry_msgs::msg::double_twist_36& covariance() const; /*! * @brief This function returns a reference to member covariance * @return Reference to member covariance */ - eProsima_user_DllExport geometry_msgs::msg::geometry_msgs__TwistWithCovariance__double_array_36& covariance(); + eProsima_user_DllExport geometry_msgs::msg::double_twist_36& covariance(); /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -197,6 +195,7 @@ namespace geometry_msgs { const geometry_msgs::msg::TwistWithCovariance& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -211,6 +210,8 @@ namespace geometry_msgs { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -233,10 +234,11 @@ namespace geometry_msgs { eprosima::fastcdr::Cdr& cdr) const; private: + geometry_msgs::msg::Twist m_twist; - geometry_msgs::msg::geometry_msgs__TwistWithCovariance__double_array_36 m_covariance; + geometry_msgs::msg::double_twist_36 m_covariance; }; } // namespace msg } // namespace geometry_msgs -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCE_H_ +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/TwistWithCovariancePubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariancePubSubTypes.cxx similarity index 89% rename from LibCarla/source/carla/ros2/types/TwistWithCovariancePubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariancePubSubTypes.cxx index e9c062decfa..a992128aef0 100644 --- a/LibCarla/source/carla/ros2/types/TwistWithCovariancePubSubTypes.cpp +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariancePubSubTypes.cxx @@ -19,6 +19,7 @@ * This file was generated by the tool fastcdrgen. */ + #include #include @@ -84,21 +85,21 @@ namespace geometry_msgs { SerializedPayload_t* payload, void* data) { - try - { - //Convert DATA to pointer of your type - TwistWithCovariance* p_type = static_cast(data); + //Convert DATA to pointer of your type + TwistWithCovariance* p_type = static_cast(data); - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); - // Deserialize encapsulation. - deser.read_encapsulation(); - payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + try + { // Deserialize the object. p_type->deserialize(deser); } @@ -169,5 +170,8 @@ namespace geometry_msgs { } return true; } + + } //End of namespace msg + } //End of namespace geometry_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariancePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariancePubSubTypes.h new file mode 100644 index 00000000000..6113b33320f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariancePubSubTypes.h @@ -0,0 +1,108 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file TwistWithCovariancePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCE_PUBSUBTYPES_H_ + +#include +#include + +#include "TwistWithCovariance.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated TwistWithCovariance is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace geometry_msgs +{ + namespace msg + { + typedef std::array double_twist_36; + /*! + * @brief This class represents the TopicDataType of the type TwistWithCovariance defined by the user in the IDL file. + * @ingroup TWISTWITHCOVARIANCE + */ + class TwistWithCovariancePubSubType : public eprosima::fastdds::dds::TopicDataType + { + public: + + typedef TwistWithCovariance type; + + eProsima_user_DllExport TwistWithCovariancePubSubType(); + + eProsima_user_DllExport virtual ~TwistWithCovariancePubSubType(); + + eProsima_user_DllExport virtual bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider( + void* data) override; + + eProsima_user_DllExport virtual bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData( + void* data) override; + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + + #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override + { + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + + #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample( + void* memory) const override + { + new (memory) TwistWithCovariance(); + return true; + } + + #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + }; + } +} + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/Vector3.cpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3.cxx similarity index 86% rename from LibCarla/source/carla/ros2/types/Vector3.cpp rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3.cxx index 2890489abfc..b1ea662638d 100644 --- a/LibCarla/source/carla/ros2/types/Vector3.cpp +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3.cxx @@ -34,21 +34,21 @@ using namespace eprosima::fastcdr::exception; #include -#define geometry_msgs_msg_Vector3_max_cdr_typesize 24ULL; -#define geometry_msgs_msg_Vector3_max_key_cdr_typesize 0ULL; - geometry_msgs::msg::Vector3::Vector3() { - // double m_x + // m_x com.eprosima.idl.parser.typecode.PrimitiveTypeCode@74d1dc36 m_x = 0.0; - // double m_y + // m_y com.eprosima.idl.parser.typecode.PrimitiveTypeCode@7161d8d1 m_y = 0.0; - // double m_z + // m_z com.eprosima.idl.parser.typecode.PrimitiveTypeCode@663c9e7a m_z = 0.0; + } geometry_msgs::msg::Vector3::~Vector3() { + + } geometry_msgs::msg::Vector3::Vector3( @@ -60,7 +60,7 @@ geometry_msgs::msg::Vector3::Vector3( } geometry_msgs::msg::Vector3::Vector3( - Vector3&& x) noexcept + Vector3&& x) { m_x = x.m_x; m_y = x.m_y; @@ -79,8 +79,9 @@ geometry_msgs::msg::Vector3& geometry_msgs::msg::Vector3::operator =( } geometry_msgs::msg::Vector3& geometry_msgs::msg::Vector3::operator =( - Vector3&& x) noexcept + Vector3&& x) { + m_x = x.m_x; m_y = x.m_y; m_z = x.m_z; @@ -91,6 +92,7 @@ geometry_msgs::msg::Vector3& geometry_msgs::msg::Vector3::operator =( bool geometry_msgs::msg::Vector3::operator ==( const Vector3& x) const { + return (m_x == x.m_x && m_y == x.m_y && m_z == x.m_z); } @@ -103,8 +105,20 @@ bool geometry_msgs::msg::Vector3::operator !=( size_t geometry_msgs::msg::Vector3::getMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return geometry_msgs_msg_Vector3_max_cdr_typesize; + size_t initial_alignment = current_alignment; + + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + + return current_alignment - initial_alignment; } size_t geometry_msgs::msg::Vector3::getCdrSerializedSize( @@ -113,24 +127,35 @@ size_t geometry_msgs::msg::Vector3::getCdrSerializedSize( { (void)data; size_t initial_alignment = current_alignment; + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + return current_alignment - initial_alignment; } void geometry_msgs::msg::Vector3::serialize( eprosima::fastcdr::Cdr& scdr) const { + scdr << m_x; scdr << m_y; scdr << m_z; + } void geometry_msgs::msg::Vector3::deserialize( eprosima::fastcdr::Cdr& dcdr) { + dcdr >> m_x; dcdr >> m_y; dcdr >> m_z; @@ -220,11 +245,15 @@ double& geometry_msgs::msg::Vector3::z() return m_z; } + size_t geometry_msgs::msg::Vector3::getKeyMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return geometry_msgs_msg_Vector3_max_key_cdr_typesize; + size_t current_align = current_alignment; + + + + return current_align; } bool geometry_msgs::msg::Vector3::isKeyDefined() @@ -236,4 +265,7 @@ void geometry_msgs::msg::Vector3::serializeKey( eprosima::fastcdr::Cdr& scdr) const { (void) scdr; + } + + diff --git a/LibCarla/source/carla/ros2/types/Vector3.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3.h similarity index 94% rename from LibCarla/source/carla/ros2/types/Vector3.h rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3.h index cb96d7843a0..4323f7f1aed 100644 --- a/LibCarla/source/carla/ros2/types/Vector3.h +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3.h @@ -22,7 +22,6 @@ #ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3_H_ #define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3_H_ -#include #include #include @@ -94,7 +93,7 @@ namespace geometry_msgs { * @param x Reference to the object geometry_msgs::msg::Vector3 that will be copied. */ eProsima_user_DllExport Vector3( - Vector3&& x) noexcept; + Vector3&& x); /*! * @brief Copy assignment. @@ -108,7 +107,7 @@ namespace geometry_msgs { * @param x Reference to the object geometry_msgs::msg::Vector3 that will be copied. */ eProsima_user_DllExport Vector3& operator =( - Vector3&& x) noexcept; + Vector3&& x); /*! * @brief Comparison operator. @@ -181,12 +180,13 @@ namespace geometry_msgs { */ eProsima_user_DllExport double& z(); + /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ eProsima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); @@ -200,6 +200,7 @@ namespace geometry_msgs { const geometry_msgs::msg::Vector3& data, size_t current_alignment = 0); + /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. @@ -214,6 +215,8 @@ namespace geometry_msgs { eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr); + + /*! * @brief This function returns the maximum serialized size of the Key of an object * depending on the buffer alignment. @@ -236,6 +239,7 @@ namespace geometry_msgs { eprosima::fastcdr::Cdr& cdr) const; private: + double m_x; double m_y; double m_z; @@ -243,4 +247,4 @@ namespace geometry_msgs { } // namespace msg } // namespace geometry_msgs -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3_H_ +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/Vector3PubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3PubSubTypes.cxx similarity index 89% rename from LibCarla/source/carla/ros2/types/Vector3PubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3PubSubTypes.cxx index 2a568e23a3f..d54cdd679ff 100644 --- a/LibCarla/source/carla/ros2/types/Vector3PubSubTypes.cpp +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3PubSubTypes.cxx @@ -19,6 +19,7 @@ * This file was generated by the tool fastcdrgen. */ + #include #include @@ -83,21 +84,21 @@ namespace geometry_msgs { SerializedPayload_t* payload, void* data) { - try - { - //Convert DATA to pointer of your type - Vector3* p_type = static_cast(data); + //Convert DATA to pointer of your type + Vector3* p_type = static_cast(data); - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); - // Deserialize encapsulation. - deser.read_encapsulation(); - payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + try + { // Deserialize the object. p_type->deserialize(deser); } @@ -168,5 +169,8 @@ namespace geometry_msgs { } return true; } + + } //End of namespace msg + } //End of namespace geometry_msgs diff --git a/LibCarla/source/carla/ros2/types/Vector3PubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3PubSubTypes.h similarity index 76% rename from LibCarla/source/carla/ros2/types/Vector3PubSubTypes.h rename to LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3PubSubTypes.h index 7a5080e9445..505a56ec972 100644 --- a/LibCarla/source/carla/ros2/types/Vector3PubSubTypes.h +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3PubSubTypes.h @@ -19,6 +19,7 @@ * This file was generated by the tool fastcdrgen. */ + #ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3_PUBSUBTYPES_H_ #define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3_PUBSUBTYPES_H_ @@ -36,36 +37,6 @@ namespace geometry_msgs { namespace msg { - - #ifndef SWIG - namespace detail { - - template - struct Vector3_rob - { - friend constexpr typename Tag::type get( - Tag) - { - return M; - } - }; - - struct Vector3_f - { - typedef double Vector3::* type; - friend constexpr type get( - Vector3_f); - }; - - template struct Vector3_rob; - - template - inline size_t constexpr Vector3_offset_of() { - return ((::size_t) &reinterpret_cast((((T*)0)->*get(Tag())))); - } - } - #endif - /*! * @brief This class represents the TopicDataType of the type Vector3 defined by the user in the IDL file. * @ingroup VECTOR3 @@ -78,7 +49,7 @@ namespace geometry_msgs eProsima_user_DllExport Vector3PubSubType(); - eProsima_user_DllExport virtual ~Vector3PubSubType() override; + eProsima_user_DllExport virtual ~Vector3PubSubType(); eProsima_user_DllExport virtual bool serialize( void* data, @@ -112,7 +83,7 @@ namespace geometry_msgs #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN eProsima_user_DllExport inline bool is_plain() const override { - return is_plain_impl(); + return true; } #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN @@ -126,15 +97,11 @@ namespace geometry_msgs } #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; unsigned char* m_keyBuffer; - private: - static constexpr bool is_plain_impl() - { - return 24ULL == (detail::Vector3_offset_of() + sizeof(double)); - - }}; + }; } } -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3_PUBSUBTYPES_H_ +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/Odometry.cpp b/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/Odometry.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/Odometry.cpp rename to LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/Odometry.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/Odometry.h b/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/Odometry.h new file mode 100644 index 00000000000..d7bcf1499b5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/Odometry.h @@ -0,0 +1,272 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Odometry.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRY_H_ +#define _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRY_H_ + +#include "geometry_msgs/msg/PoseWithCovariance.h" +#include "geometry_msgs/msg/TwistWithCovariance.h" +#include "std_msgs/msg/Header.h" + +#include + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(Odometry_SOURCE) +#define Odometry_DllAPI __declspec(dllexport) +#else +#define Odometry_DllAPI __declspec(dllimport) +#endif // Odometry_SOURCE +#else +#define Odometry_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define Odometry_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace nav_msgs { +namespace msg { +/*! + * @brief This class represents the structure Odometry defined by the user in the IDL file. + * @ingroup ODOMETRY + */ +class Odometry { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Odometry(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Odometry(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object nav_msgs::msg::Odometry that will be copied. + */ + eProsima_user_DllExport Odometry(const Odometry& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object nav_msgs::msg::Odometry that will be copied. + */ + eProsima_user_DllExport Odometry(Odometry&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object nav_msgs::msg::Odometry that will be copied. + */ + eProsima_user_DllExport Odometry& operator=(const Odometry& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object nav_msgs::msg::Odometry that will be copied. + */ + eProsima_user_DllExport Odometry& operator=(Odometry&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x nav_msgs::msg::Odometry object to compare. + */ + eProsima_user_DllExport bool operator==(const Odometry& x) const; + + /*! + * @brief Comparison operator. + * @param x nav_msgs::msg::Odometry object to compare. + */ + eProsima_user_DllExport bool operator!=(const Odometry& x) const; + + /*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ + eProsima_user_DllExport void header(const std_msgs::msg::Header& _header); + + /*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ + eProsima_user_DllExport void header(std_msgs::msg::Header&& _header); + + /*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ + eProsima_user_DllExport const std_msgs::msg::Header& header() const; + + /*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ + eProsima_user_DllExport std_msgs::msg::Header& header(); + /*! + * @brief This function copies the value in member child_frame_id + * @param _child_frame_id New value to be copied in member child_frame_id + */ + eProsima_user_DllExport void child_frame_id(const std::string& _child_frame_id); + + /*! + * @brief This function moves the value in member child_frame_id + * @param _child_frame_id New value to be moved in member child_frame_id + */ + eProsima_user_DllExport void child_frame_id(std::string&& _child_frame_id); + + /*! + * @brief This function returns a constant reference to member child_frame_id + * @return Constant reference to member child_frame_id + */ + eProsima_user_DllExport const std::string& child_frame_id() const; + + /*! + * @brief This function returns a reference to member child_frame_id + * @return Reference to member child_frame_id + */ + eProsima_user_DllExport std::string& child_frame_id(); + /*! + * @brief This function copies the value in member pose + * @param _pose New value to be copied in member pose + */ + eProsima_user_DllExport void pose(const geometry_msgs::msg::PoseWithCovariance& _pose); + + /*! + * @brief This function moves the value in member pose + * @param _pose New value to be moved in member pose + */ + eProsima_user_DllExport void pose(geometry_msgs::msg::PoseWithCovariance&& _pose); + + /*! + * @brief This function returns a constant reference to member pose + * @return Constant reference to member pose + */ + eProsima_user_DllExport const geometry_msgs::msg::PoseWithCovariance& pose() const; + + /*! + * @brief This function returns a reference to member pose + * @return Reference to member pose + */ + eProsima_user_DllExport geometry_msgs::msg::PoseWithCovariance& pose(); + /*! + * @brief This function copies the value in member twist + * @param _twist New value to be copied in member twist + */ + eProsima_user_DllExport void twist(const geometry_msgs::msg::TwistWithCovariance& _twist); + + /*! + * @brief This function moves the value in member twist + * @param _twist New value to be moved in member twist + */ + eProsima_user_DllExport void twist(geometry_msgs::msg::TwistWithCovariance&& _twist); + + /*! + * @brief This function returns a constant reference to member twist + * @return Constant reference to member twist + */ + eProsima_user_DllExport const geometry_msgs::msg::TwistWithCovariance& twist() const; + + /*! + * @brief This function returns a reference to member twist + * @return Reference to member twist + */ + eProsima_user_DllExport geometry_msgs::msg::TwistWithCovariance& twist(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const nav_msgs::msg::Odometry& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + std_msgs::msg::Header m_header; + std::string m_child_frame_id; + geometry_msgs::msg::PoseWithCovariance m_pose; + geometry_msgs::msg::TwistWithCovariance m_twist; +}; +} // namespace msg +} // namespace nav_msgs + +#endif // _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRY_H_ diff --git a/LibCarla/source/carla/ros2/types/OdometryPubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/OdometryPubSubTypes.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/OdometryPubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/OdometryPubSubTypes.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/OdometryPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/OdometryPubSubTypes.h new file mode 100644 index 00000000000..faafa5dfa36 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/OdometryPubSubTypes.h @@ -0,0 +1,94 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file OdometryPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRY_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRY_PUBSUBTYPES_H_ + +#include +#include + +#include "Odometry.h" +#include "geometry_msgs/msg/PoseWithCovariancePubSubTypes.h" +#include "geometry_msgs/msg/TwistWithCovariancePubSubTypes.h" +#include "std_msgs/msg/HeaderPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated Odometry is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace nav_msgs { +namespace msg { + +/*! + * @brief This class represents the TopicDataType of the type Odometry defined by the user in the IDL file. + * @ingroup ODOMETRY + */ +class OdometryPubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef Odometry type; + + eProsima_user_DllExport OdometryPubSubType(); + + eProsima_user_DllExport virtual ~OdometryPubSubType() override; + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + (void)memory; + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; + unsigned char* m_keyBuffer; +}; +} // namespace msg +} // namespace nav_msgs + +#endif // _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRY_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/Clock.cpp b/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/Clock.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/Clock.cpp rename to LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/Clock.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/Clock.h b/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/Clock.h new file mode 100644 index 00000000000..88cd6b74253 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/Clock.h @@ -0,0 +1,198 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Clock.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_ROSGRAPH_MSG_CLOCK_H_ +#define _FAST_DDS_GENERATED_ROSGRAPH_MSG_CLOCK_H_ + +#include "builtin_interfaces/msg/Time.h" + +#include + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CLOCK_SOURCE) +#define CLOCK_DllAPI __declspec(dllexport) +#else +#define CLOCK_DllAPI __declspec(dllimport) +#endif // CLOCK_SOURCE +#else +#define CLOCK_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CLOCK_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace rosgraph { +namespace msg { +/*! + * @brief This class represents the structure Clock defined by the user in the IDL file. + * @ingroup Clock + */ +class Clock { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Clock(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Clock(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object rosgraph::msg::Clock that will be copied. + */ + eProsima_user_DllExport Clock(const Clock& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object rosgraph::msg::Clock that will be copied. + */ + eProsima_user_DllExport Clock(Clock&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object rosgraph::msg::Clock that will be copied. + */ + eProsima_user_DllExport Clock& operator=(const Clock& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object rosgraph::msg::Clock that will be copied. + */ + eProsima_user_DllExport Clock& operator=(Clock&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x rosgraph::msg::Clock object to compare. + */ + eProsima_user_DllExport bool operator==(const Clock& x) const; + + /*! + * @brief Comparison operator. + * @param x rosgraph::msg::Clock object to compare. + */ + eProsima_user_DllExport bool operator!=(const Clock& x) const; + + /*! + * @brief This function copies the value in member clock + * @param _clock New value to be copied in member clock + */ + eProsima_user_DllExport void clock(const builtin_interfaces::msg::Time& _clock); + + /*! + * @brief This function moves the value in member clock + * @param _clock New value to be moved in member clock + */ + eProsima_user_DllExport void clock(builtin_interfaces::msg::Time&& _clock); + + /*! + * @brief This function returns a constant reference to member clock + * @return Constant reference to member clock + */ + eProsima_user_DllExport const builtin_interfaces::msg::Time& clock() const; + + /*! + * @brief This function returns a reference to member clock + * @return Reference to member clock + */ + eProsima_user_DllExport builtin_interfaces::msg::Time& clock(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const rosgraph::msg::Clock& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + builtin_interfaces::msg::Time m_clock; +}; +} // namespace msg +} // namespace rosgraph + +#endif // _FAST_DDS_GENERATED_ROSGRAPH_MSG_CLOCK_H_ diff --git a/LibCarla/source/carla/ros2/types/ClockPubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/ClockPubSubTypes.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/ClockPubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/ClockPubSubTypes.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/ClockPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/ClockPubSubTypes.h new file mode 100644 index 00000000000..ea836ebdca0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/ClockPubSubTypes.h @@ -0,0 +1,90 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ClockPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_ROSGRAPH_MSG_CLOCK_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ROSGRAPH_MSG_CLOCK_PUBSUBTYPES_H_ + +#include +#include + +#include "Clock.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated Clock is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace rosgraph { +namespace msg { +/*! + * @brief This class represents the TopicDataType of the type Clock defined by the user in the IDL file. + * @ingroup Clock + */ +class ClockPubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef Clock type; + + eProsima_user_DllExport ClockPubSubType(); + + eProsima_user_DllExport virtual ~ClockPubSubType() override; + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + (void)memory; + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; + unsigned char* m_keyBuffer; +}; +} // namespace msg +} // namespace rosgraph + +#endif // _FAST_DDS_GENERATED_ROSGRAPH_MSG_CLOCK_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/CameraInfo.cpp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfo.cxx similarity index 98% rename from LibCarla/source/carla/ros2/types/CameraInfo.cpp rename to LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfo.cxx index 058e88d3bd3..e6893ee2aff 100644 --- a/LibCarla/source/carla/ros2/types/CameraInfo.cpp +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfo.cxx @@ -19,6 +19,9 @@ * This file was generated by the tool gen. */ +#define _USE_MATH_DEFINES +#include + #ifdef _WIN32 // Remove linker warning LNK4221 on Visual Studio namespace { @@ -26,6 +29,10 @@ char dummy; } // namespace #endif // _WIN32 +// ensure that cmath header is not included elsewhere before to enable the math definitions on Win32 +#define _USE_MATH_DEFINES +#include + #include "CameraInfo.h" #include @@ -33,7 +40,6 @@ char dummy; using namespace eprosima::fastcdr::exception; #include -#include #define builtin_interfaces_msg_Time_max_cdr_typesize 8ULL; #define sensor_msgs_msg_CameraInfo_max_cdr_typesize 3793ULL; diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfo.h b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfo.h new file mode 100644 index 00000000000..39016b4d3ca --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfo.h @@ -0,0 +1,419 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CameraInfo.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFO_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFO_H_ + +#include "sensor_msgs/msg/RegionOfInterest.h" +#include "std_msgs/msg/Header.h" + +#include + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(CAMERAINFO_SOURCE) +#define CAMERAINFO_DllAPI __declspec(dllexport) +#else +#define CAMERAINFO_DllAPI __declspec(dllimport) +#endif // CAMERAINFO_SOURCE +#else +#define CAMERAINFO_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CAMERAINFO_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace sensor_msgs { +namespace msg { +/*! + * @brief This class represents the structure CameraInfo defined by the user in the IDL file. + * @ingroup CameraInfo + */ +class CameraInfo { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CameraInfo(uint32_t height = 0, uint32_t width = 0, double fov = 0.0); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CameraInfo(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object sensor_msgs::msg::CameraInfo that will be copied. + */ + eProsima_user_DllExport CameraInfo(const CameraInfo& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object sensor_msgs::msg::CameraInfo that will be copied. + */ + eProsima_user_DllExport CameraInfo(CameraInfo&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object sensor_msgs::msg::CameraInfo that will be copied. + */ + eProsima_user_DllExport CameraInfo& operator=(const CameraInfo& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object sensor_msgs::msg::CameraInfo that will be copied. + */ + eProsima_user_DllExport CameraInfo& operator=(CameraInfo&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x sensor_msgs::msg::CameraInfo object to compare. + */ + eProsima_user_DllExport bool operator==(const CameraInfo& x) const; + + /*! + * @brief Comparison operator. + * @param x sensor_msgs::msg::CameraInfo object to compare. + */ + eProsima_user_DllExport bool operator!=(const CameraInfo& x) const; + + /*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ + eProsima_user_DllExport void header(const std_msgs::msg::Header& _header); + + /*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ + eProsima_user_DllExport void header(std_msgs::msg::Header&& _header); + + /*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ + eProsima_user_DllExport const std_msgs::msg::Header& header() const; + + /*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ + eProsima_user_DllExport std_msgs::msg::Header& header(); + /*! + * @brief This function sets a value in member height + * @param _height New value for member height + */ + eProsima_user_DllExport void height(uint32_t _height); + + /*! + * @brief This function returns the value of member height + * @return Value of member height + */ + eProsima_user_DllExport uint32_t height() const; + + /*! + * @brief This function returns a reference to member height + * @return Reference to member height + */ + eProsima_user_DllExport uint32_t& height(); + + /*! + * @brief This function sets a value in member width + * @param _width New value for member width + */ + eProsima_user_DllExport void width(uint32_t _width); + + /*! + * @brief This function returns the value of member width + * @return Value of member width + */ + eProsima_user_DllExport uint32_t width() const; + + /*! + * @brief This function returns a reference to member width + * @return Reference to member width + */ + eProsima_user_DllExport uint32_t& width(); + + /*! + * @brief This function copies the value in member distortion_model + * @param _distortion_model New value to be copied in member distortion_model + */ + eProsima_user_DllExport void distortion_model(const std::string& _distortion_model); + + /*! + * @brief This function moves the value in member distortion_model + * @param _distortion_model New value to be moved in member distortion_model + */ + eProsima_user_DllExport void distortion_model(std::string&& _distortion_model); + + /*! + * @brief This function returns a constant reference to member distortion_model + * @return Constant reference to member distortion_model + */ + eProsima_user_DllExport const std::string& distortion_model() const; + + /*! + * @brief This function returns a reference to member distortion_model + * @return Reference to member distortion_model + */ + eProsima_user_DllExport std::string& distortion_model(); + /*! + * @brief This function copies the value in member D + * @param _D New value to be copied in member D + */ + eProsima_user_DllExport void D(const std::vector& _D); + + /*! + * @brief This function moves the value in member D + * @param _D New value to be moved in member D + */ + eProsima_user_DllExport void D(std::vector&& _D); + + /*! + * @brief This function returns a constant reference to member D + * @return Constant reference to member D + */ + eProsima_user_DllExport const std::vector& D() const; + + /*! + * @brief This function returns a reference to member D + * @return Reference to member D + */ + eProsima_user_DllExport std::vector& D(); + /*! + * @brief This function copies the value in member K + * @param _K New value to be copied in member K + */ + eProsima_user_DllExport void k(const std::array& _k); + + /*! + * @brief This function moves the value in member k + * @param _k New value to be moved in member k + */ + eProsima_user_DllExport void k(std::array&& _k); + + /*! + * @brief This function returns a constant reference to member k + * @return Constant reference to member k + */ + eProsima_user_DllExport const std::array& k() const; + + /*! + * @brief This function returns a reference to member k + * @return Reference to member k + */ + eProsima_user_DllExport std::array& k(); + /*! + * @brief This function copies the value in member r + * @param _r New value to be copied in member r + */ + eProsima_user_DllExport void r(const std::array& _r); + + /*! + * @brief This function moves the value in member r + * @param _r New value to be moved in member r + */ + eProsima_user_DllExport void r(std::array&& _r); + + /*! + * @brief This function returns a constant reference to member r + * @return Constant reference to member r + */ + eProsima_user_DllExport const std::array& r() const; + + /*! + * @brief This function returns a reference to member r + * @return Reference to member r + */ + eProsima_user_DllExport std::array& r(); + /*! + * @brief This function copies the value in member p + * @param _p New value to be copied in member p + */ + eProsima_user_DllExport void p(const std::array& _p); + + /*! + * @brief This function moves the value in member p + * @param _p New value to be moved in member p + */ + eProsima_user_DllExport void p(std::array&& _p); + + /*! + * @brief This function returns a constant reference to member p + * @return Constant reference to member p + */ + eProsima_user_DllExport const std::array& p() const; + + /*! + * @brief This function returns a reference to member p + * @return Reference to member p + */ + eProsima_user_DllExport std::array& p(); + /*! + * @brief This function sets a value in member binning_x + * @param _binning_x New value for member binning_x + */ + eProsima_user_DllExport void binning_x(uint32_t _binning_x); + + /*! + * @brief This function returns the value of member binning_x + * @return Value of member binning_x + */ + eProsima_user_DllExport uint32_t binning_x() const; + + /*! + * @brief This function returns a reference to member binning_x + * @return Reference to member binning_x + */ + eProsima_user_DllExport uint32_t& binning_x(); + + /*! + * @brief This function sets a value in member binning_y + * @param _binning_y New value for member binning_y + */ + eProsima_user_DllExport void binning_y(uint32_t _binning_y); + + /*! + * @brief This function returns the value of member binning_y + * @return Value of member binning_y + */ + eProsima_user_DllExport uint32_t binning_y() const; + + /*! + * @brief This function returns a reference to member binning_y + * @return Reference to member binning_y + */ + eProsima_user_DllExport uint32_t& binning_y(); + + /*! + * @brief This function copies the value in member roi + * @param _roi New value to be copied in member roi + */ + eProsima_user_DllExport void roi(const sensor_msgs::msg::RegionOfInterest& _roi); + + /*! + * @brief This function moves the value in member roi + * @param _roi New value to be moved in member roi + */ + eProsima_user_DllExport void roi(sensor_msgs::msg::RegionOfInterest&& _roi); + + /*! + * @brief This function returns a constant reference to member roi + * @return Constant reference to member roi + */ + eProsima_user_DllExport const sensor_msgs::msg::RegionOfInterest& roi() const; + + /*! + * @brief This function returns a reference to member roi + * @return Reference to member roi + */ + eProsima_user_DllExport sensor_msgs::msg::RegionOfInterest& roi(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const sensor_msgs::msg::CameraInfo& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + std_msgs::msg::Header m_header; + uint32_t m_height; + uint32_t m_width; + std::string m_distortion_model; + std::vector m_d; + std::array m_k; + std::array m_r; + std::array m_p; + uint32_t m_binning_x; + uint32_t m_binning_y; + sensor_msgs::msg::RegionOfInterest m_roi; +}; +} // namespace msg +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFO_H_ diff --git a/LibCarla/source/carla/ros2/types/CameraInfoPubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfoPubSubTypes.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/CameraInfoPubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfoPubSubTypes.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfoPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfoPubSubTypes.h new file mode 100644 index 00000000000..50d03342fad --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfoPubSubTypes.h @@ -0,0 +1,93 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file CameraInfoPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFO_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFO_PUBSUBTYPES_H_ + +#include +#include + +#include "CameraInfo.h" + +#include "RegionOfInterestPubSubTypes.h" +#include "std_msgs/msg/HeaderPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated CameraInfo is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace sensor_msgs { +namespace msg { +/*! + * @brief This class represents the TopicDataType of the type CameraInfo defined by the user in the IDL file. + * @ingroup CameraInfo + */ +class CameraInfoPubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef CameraInfo type; + + eProsima_user_DllExport CameraInfoPubSubType(); + + eProsima_user_DllExport virtual ~CameraInfoPubSubType() override; + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + (void)memory; + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; + unsigned char* m_keyBuffer; +}; +} // namespace msg +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFO_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/Image.cc b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/Image.cc new file mode 100644 index 00000000000..e607e9f9e40 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/Image.cc @@ -0,0 +1,397 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Image.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +// char dummy; +} // namespace +#endif // _WIN32 + +#include "Image.h" +#include + +#include + +#define builtin_interfaces_msg_Time_max_cdr_typesize 8ULL; +#define sensor_msgs_msg_Image_max_cdr_typesize 648ULL; +#define std_msgs_msg_Header_max_cdr_typesize 268ULL; +#define builtin_interfaces_msg_Time_max_key_cdr_typesize 0ULL; +#define sensor_msgs_msg_Image_max_key_cdr_typesize 0ULL; +#define std_msgs_msg_Header_max_key_cdr_typesize 0ULL; + +template +sensor_msgs::msg::ImageT::ImageT() { + // std_msgs::msg::Header m_header + + // unsigned long m_height + m_height = 0; + // unsigned long m_width + m_width = 0; + // string m_encoding + m_encoding = ""; + // uint8 m_is_bigendian + m_is_bigendian = 0; + // unsigned long m_step + m_step = 0; + // sequence m_data +} + +template +sensor_msgs::msg::ImageT::~ImageT() {} + +template +sensor_msgs::msg::ImageT::ImageT(const ImageT& x) { + m_header = x.m_header; + m_height = x.m_height; + m_width = x.m_width; + m_encoding = x.m_encoding; + m_is_bigendian = x.m_is_bigendian; + m_step = x.m_step; + m_data = x.m_data; +} + +template +sensor_msgs::msg::ImageT::ImageT(ImageT&& x) noexcept { + m_header = std::move(x.m_header); + m_height = x.m_height; + m_width = x.m_width; + m_encoding = std::move(x.m_encoding); + m_is_bigendian = x.m_is_bigendian; + m_step = x.m_step; + m_data = std::move(x.m_data); +} + +template +sensor_msgs::msg::ImageT& sensor_msgs::msg::ImageT::operator=(const ImageT& x) { + m_header = x.m_header; + m_height = x.m_height; + m_width = x.m_width; + m_encoding = x.m_encoding; + m_is_bigendian = x.m_is_bigendian; + m_step = x.m_step; + m_data = x.m_data; + + return *this; +} + +template +sensor_msgs::msg::ImageT& sensor_msgs::msg::ImageT::operator=(ImageT&& x) noexcept { + m_header = std::move(x.m_header); + m_height = x.m_height; + m_width = x.m_width; + m_encoding = std::move(x.m_encoding); + m_is_bigendian = x.m_is_bigendian; + m_step = x.m_step; + m_data = std::move(x.m_data); + + return *this; +} + +template +bool sensor_msgs::msg::ImageT::operator==(const ImageT& x) const { + return (m_header == x.m_header && m_height == x.m_height && m_width == x.m_width && m_encoding == x.m_encoding && + m_is_bigendian == x.m_is_bigendian && m_step == x.m_step && m_data == x.m_data); +} + +template +bool sensor_msgs::msg::ImageT::operator!=(const ImageT& x) const { + return !(*this == x); +} + +template +size_t sensor_msgs::msg::ImageT::getMaxCdrSerializedSize(size_t current_alignment) { + static_cast(current_alignment); + return sensor_msgs_msg_Image_max_cdr_typesize; +} + +template +size_t sensor_msgs::msg::ImageT::getCdrSerializedSize(const sensor_msgs::msg::ImageT& data, + size_t current_alignment) { + size_t initial_alignment = current_alignment; + current_alignment += std_msgs::msg::Header::getCdrSerializedSize(data.header(), current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.encoding().size() + 1; + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + if (data.data().size() > 0) { + current_alignment += (data.data().size() * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + } + + return current_alignment - initial_alignment; +} + +template +void sensor_msgs::msg::ImageT::serialize(eprosima::fastcdr::Cdr& scdr) const { + scdr << m_header; + scdr << m_height; + scdr << m_width; + scdr << m_encoding.c_str(); + scdr << m_is_bigendian; + scdr << m_step; + scdr << m_data; +} + +template +void sensor_msgs::msg::ImageT::deserialize(eprosima::fastcdr::Cdr& dcdr) { + dcdr >> m_header; + dcdr >> m_height; + dcdr >> m_width; + dcdr >> m_encoding; + dcdr >> m_is_bigendian; + dcdr >> m_step; + dcdr >> m_data; +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +template +void sensor_msgs::msg::ImageT::header(const std_msgs::msg::Header& _header) { + m_header = _header; +} + +/*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ +template +void sensor_msgs::msg::ImageT::header(std_msgs::msg::Header&& _header) { + m_header = std::move(_header); +} + +/*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ +template +const std_msgs::msg::Header& sensor_msgs::msg::ImageT::header() const { + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +template +std_msgs::msg::Header& sensor_msgs::msg::ImageT::header() { + return m_header; +} + +/*! + * @brief This function sets a value in member height + * @param _height New value for member height + */ +template +void sensor_msgs::msg::ImageT::height(uint32_t _height) { + m_height = _height; +} + +/*! + * @brief This function returns the value of member height + * @return Value of member height + */ +template +uint32_t sensor_msgs::msg::ImageT::height() const { + return m_height; +} + +/*! + * @brief This function returns a reference to member height + * @return Reference to member height + */ +template +uint32_t& sensor_msgs::msg::ImageT::height() { + return m_height; +} + +/*! + * @brief This function sets a value in member width + * @param _width New value for member width + */ +template +void sensor_msgs::msg::ImageT::width(uint32_t _width) { + m_width = _width; +} + +/*! + * @brief This function returns the value of member width + * @return Value of member width + */ +template +uint32_t sensor_msgs::msg::ImageT::width() const { + return m_width; +} + +/*! + * @brief This function returns a reference to member width + * @return Reference to member width + */ +template +uint32_t& sensor_msgs::msg::ImageT::width() { + return m_width; +} + +/*! + * @brief This function copies the value in member encoding + * @param _encoding New value to be copied in member encoding + */ +template +void sensor_msgs::msg::ImageT::encoding(const std::string& _encoding) { + m_encoding = _encoding; +} + +/*! + * @brief This function moves the value in member encoding + * @param _encoding New value to be moved in member encoding + */ +template +void sensor_msgs::msg::ImageT::encoding(std::string&& _encoding) { + m_encoding = std::move(_encoding); +} + +/*! + * @brief This function returns a constant reference to member encoding + * @return Constant reference to member encoding + */ +template +const std::string& sensor_msgs::msg::ImageT::encoding() const { + return m_encoding; +} + +/*! + * @brief This function returns a reference to member encoding + * @return Reference to member encoding + */ +template +std::string& sensor_msgs::msg::ImageT::encoding() { + return m_encoding; +} + +/*! + * @brief This function sets a value in member is_bigendian + * @param _is_bigendian New value for member is_bigendian + */ +template +void sensor_msgs::msg::ImageT::is_bigendian(uint8_t _is_bigendian) { + m_is_bigendian = _is_bigendian; +} + +/*! + * @brief This function returns the value of member is_bigendian + * @return Value of member is_bigendian + */ +template +uint8_t sensor_msgs::msg::ImageT::is_bigendian() const { + return m_is_bigendian; +} + +/*! + * @brief This function returns a reference to member is_bigendian + * @return Reference to member is_bigendian + */ +template +uint8_t& sensor_msgs::msg::ImageT::is_bigendian() { + return m_is_bigendian; +} + +/*! + * @brief This function sets a value in member step + * @param _step New value for member step + */ +template +void sensor_msgs::msg::ImageT::step(uint32_t _step) { + m_step = _step; +} + +/*! + * @brief This function returns the value of member step + * @return Value of member step + */ +template +uint32_t sensor_msgs::msg::ImageT::step() const { + return m_step; +} + +/*! + * @brief This function returns a reference to member step + * @return Reference to member step + */ +template +uint32_t& sensor_msgs::msg::ImageT::step() { + return m_step; +} + +/*! + * @brief This function copies the value in member data + * @param _data New value to be copied in member data + */ +template +void sensor_msgs::msg::ImageT::data(const typename sensor_msgs::msg::ImageT::vector_type& _data) { + m_data = _data; +} + +/*! + * @brief This function moves the value in member data + * @param _data New value to be moved in member data + */ +template +void sensor_msgs::msg::ImageT::data(typename sensor_msgs::msg::ImageT::vector_type&& _data) { + m_data = std::move(_data); +} + +/*! + * @brief This function returns a constant reference to member data + * @return Constant reference to member data + */ +template +const typename sensor_msgs::msg::ImageT::vector_type& sensor_msgs::msg::ImageT::data() const { + return m_data; +} + +/*! + * @brief This function returns a reference to member data + * @return Reference to member data + */ +template +typename sensor_msgs::msg::ImageT::vector_type& sensor_msgs::msg::ImageT::data() { + return m_data; +} + +template +size_t sensor_msgs::msg::ImageT::getKeyMaxCdrSerializedSize(size_t current_alignment) { + static_cast(current_alignment); + return sensor_msgs_msg_Image_max_key_cdr_typesize; +} + +template +bool sensor_msgs::msg::ImageT::isKeyDefined() { + return false; +} + +template +void sensor_msgs::msg::ImageT::serializeKey(eprosima::fastcdr::Cdr& scdr) const { + (void)scdr; +} diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/Image.h b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/Image.h new file mode 100644 index 00000000000..56482e3eb90 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/Image.h @@ -0,0 +1,335 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ImageT.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_ImageT_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_ImageT_H_ + +#include "std_msgs/msg/Header.h" + +#include + +#include +#include +#include +#include +#include +#include + +#include "carla/sensor/data/SerializerVectorAllocator.h" + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(ImageT_SOURCE) +#define ImageT_DllAPI __declspec(dllexport) +#else +#define ImageT_DllAPI __declspec(dllimport) +#endif // ImageT_SOURCE +#else +#define ImageT_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define ImageT_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace sensor_msgs { +namespace msg { +/*! + * @brief This class represents the structure ImageT defined by the user in the IDL file. + * @ingroup ImageT + */ +template +class ImageT { +public: + using base_type = uint8_t; + using allocator_type = ALLOCATOR; + using vector_type = std::vector; + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport ImageT(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~ImageT(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object sensor_msgs::msg::ImageT that will be copied. + */ + eProsima_user_DllExport ImageT(const ImageT& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object sensor_msgs::msg::ImageT that will be copied. + */ + eProsima_user_DllExport ImageT(ImageT&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object sensor_msgs::msg::ImageT that will be copied. + */ + eProsima_user_DllExport ImageT& operator=(const ImageT& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object sensor_msgs::msg::ImageT that will be copied. + */ + eProsima_user_DllExport ImageT& operator=(ImageT&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x sensor_msgs::msg::ImageT object to compare. + */ + eProsima_user_DllExport bool operator==(const ImageT& x) const; + + /*! + * @brief Comparison operator. + * @param x sensor_msgs::msg::ImageT object to compare. + */ + eProsima_user_DllExport bool operator!=(const ImageT& x) const; + + /*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ + eProsima_user_DllExport void header(const std_msgs::msg::Header& _header); + + /*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ + eProsima_user_DllExport void header(std_msgs::msg::Header&& _header); + + /*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ + eProsima_user_DllExport const std_msgs::msg::Header& header() const; + + /*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ + eProsima_user_DllExport std_msgs::msg::Header& header(); + /*! + * @brief This function sets a value in member height + * @param _height New value for member height + */ + eProsima_user_DllExport void height(uint32_t _height); + + /*! + * @brief This function returns the value of member height + * @return Value of member height + */ + eProsima_user_DllExport uint32_t height() const; + + /*! + * @brief This function returns a reference to member height + * @return Reference to member height + */ + eProsima_user_DllExport uint32_t& height(); + + /*! + * @brief This function sets a value in member width + * @param _width New value for member width + */ + eProsima_user_DllExport void width(uint32_t _width); + + /*! + * @brief This function returns the value of member width + * @return Value of member width + */ + eProsima_user_DllExport uint32_t width() const; + + /*! + * @brief This function returns a reference to member width + * @return Reference to member width + */ + eProsima_user_DllExport uint32_t& width(); + + /*! + * @brief This function copies the value in member encoding + * @param _encoding New value to be copied in member encoding + */ + eProsima_user_DllExport void encoding(const std::string& _encoding); + + /*! + * @brief This function moves the value in member encoding + * @param _encoding New value to be moved in member encoding + */ + eProsima_user_DllExport void encoding(std::string&& _encoding); + + /*! + * @brief This function returns a constant reference to member encoding + * @return Constant reference to member encoding + */ + eProsima_user_DllExport const std::string& encoding() const; + + /*! + * @brief This function returns a reference to member encoding + * @return Reference to member encoding + */ + eProsima_user_DllExport std::string& encoding(); + /*! + * @brief This function sets a value in member is_bigendian + * @param _is_bigendian New value for member is_bigendian + */ + eProsima_user_DllExport void is_bigendian(uint8_t _is_bigendian); + + /*! + * @brief This function returns the value of member is_bigendian + * @return Value of member is_bigendian + */ + eProsima_user_DllExport uint8_t is_bigendian() const; + + /*! + * @brief This function returns a reference to member is_bigendian + * @return Reference to member is_bigendian + */ + eProsima_user_DllExport uint8_t& is_bigendian(); + + /*! + * @brief This function sets a value in member step + * @param _step New value for member step + */ + eProsima_user_DllExport void step(uint32_t _step); + + /*! + * @brief This function returns the value of member step + * @return Value of member step + */ + eProsima_user_DllExport uint32_t step() const; + + /*! + * @brief This function returns a reference to member step + * @return Reference to member step + */ + eProsima_user_DllExport uint32_t& step(); + + /*! + * @brief This function copies the value in member data + * @param _data New value to be copied in member data + */ + eProsima_user_DllExport void data(const vector_type& _data); + + /*! + * @brief This function moves the value in member data + * @param _data New value to be moved in member data + */ + eProsima_user_DllExport void data(vector_type&& _data); + + /*! + * @brief This function returns a constant reference to member data + * @return Constant reference to member data + */ + eProsima_user_DllExport const vector_type& data() const; + + /*! + * @brief This function returns a reference to member data + * @return Reference to member data + */ + eProsima_user_DllExport vector_type& data(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const sensor_msgs::msg::ImageT& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + std_msgs::msg::Header m_header; + uint32_t m_height; + uint32_t m_width; + std::string m_encoding; + uint8_t m_is_bigendian; + uint32_t m_step; + vector_type m_data; +}; + +using ImageFromBuffer = ImageT>; +using Image = ImageT>; + +} // namespace msg +} // namespace sensor_msgs + +#include "Image.cc" + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_ImageT_H_ diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImagePubSubTypes.cc b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImagePubSubTypes.cc new file mode 100644 index 00000000000..e806b137209 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImagePubSubTypes.cc @@ -0,0 +1,135 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ImagePubSubTypeTs.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#include +#include + +#include "ImagePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace sensor_msgs { +namespace msg { + +template +ImagePubSubTypeT::ImagePubSubTypeT() { + setName("sensor_msgs::msg::dds_::Image_"); + auto type_size = type::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = type::isKeyDefined(); + size_t keyLength = type::getKeyMaxCdrSerializedSize() > 16 ? type::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); +} + +template +ImagePubSubTypeT::~ImagePubSubTypeT() { + if (m_keyBuffer != nullptr) { + free(m_keyBuffer); + } +} + +template +bool ImagePubSubTypeT::serialize(void* data, SerializedPayload_t* payload) { + type* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + p_type->serialize(ser); + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; +} + +template +bool ImagePubSubTypeT::deserialize(SerializedPayload_t* payload, void* data) { + // Convert DATA to pointer of your type + type* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + p_type->deserialize(deser); + return true; +} + +template +std::function ImagePubSubTypeT::getSerializedSizeProvider(void* data) { + return [data]() -> uint32_t { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + 4u /*encapsulation*/; + }; +} + +template +void* ImagePubSubTypeT::createData() { + return reinterpret_cast(new type()); +} + +template +void ImagePubSubTypeT::deleteData(void* data) { + delete (reinterpret_cast(data)); +} + +template +bool ImagePubSubTypeT::getKey(void* data, InstanceHandle_t* handle, bool force_md5) { + if (!m_isGetKeyDefined) { + return false; + } + + type* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), type::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || type::getKeyMaxCdrSerializedSize() > 16) { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) { + handle->value[i] = m_md5.digest[i]; + } + } else { + for (uint8_t i = 0; i < 16; ++i) { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; +} +} // End of namespace msg +} // End of namespace sensor_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImagePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImagePubSubTypes.h new file mode 100644 index 00000000000..ce3b3026495 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImagePubSubTypes.h @@ -0,0 +1,96 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ImagePubSubTypeTs.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGE_PUBSUBTYPES_H_ + +#include +#include + +#include "Image.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated Image is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace sensor_msgs { +namespace msg { +/*! + * @brief This class represents the TopicDataType of the type Image defined by the user in the IDL file. + * @ingroup IMAGE + */ +template +class ImagePubSubTypeT : public eprosima::fastdds::dds::TopicDataType { +public: + typedef ImageT type; + + eProsima_user_DllExport ImagePubSubTypeT(); + + eProsima_user_DllExport virtual ~ImagePubSubTypeT() override; + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + (void)memory; + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; + unsigned char* m_keyBuffer; +}; + +using ImagePubSubTypeFromBuffer = ImagePubSubTypeT>; +using ImagePubSubType = ImagePubSubTypeT>; +} // namespace msg +} // namespace sensor_msgs + +#include "ImagePubSubTypes.cc" + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGE_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/Imu.cpp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/Imu.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/Imu.cpp rename to LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/Imu.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/Imu.h b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/Imu.h new file mode 100644 index 00000000000..59a1a5ec242 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/Imu.h @@ -0,0 +1,352 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Imu.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMU_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMU_H_ + +#include "geometry_msgs/msg/Quaternion.h" +#include "geometry_msgs/msg/Vector3.h" +#include "std_msgs/msg/Header.h" + +#include + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(Imu_SOURCE) +#define Imu_DllAPI __declspec(dllexport) +#else +#define Imu_DllAPI __declspec(dllimport) +#endif // Imu_SOURCE +#else +#define Imu_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define Imu_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace sensor_msgs { +namespace msg { +typedef std::array sensor_msgs__Imu__double_array_9; +/*! + * @brief This class represents the structure Imu defined by the user in the IDL file. + * @ingroup IMU + */ +class Imu { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Imu(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Imu(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object sensor_msgs::msg::Imu that will be copied. + */ + eProsima_user_DllExport Imu(const Imu& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object sensor_msgs::msg::Imu that will be copied. + */ + eProsima_user_DllExport Imu(Imu&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object sensor_msgs::msg::Imu that will be copied. + */ + eProsima_user_DllExport Imu& operator=(const Imu& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object sensor_msgs::msg::Imu that will be copied. + */ + eProsima_user_DllExport Imu& operator=(Imu&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x sensor_msgs::msg::Imu object to compare. + */ + eProsima_user_DllExport bool operator==(const Imu& x) const; + + /*! + * @brief Comparison operator. + * @param x sensor_msgs::msg::Imu object to compare. + */ + eProsima_user_DllExport bool operator!=(const Imu& x) const; + + /*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ + eProsima_user_DllExport void header(const std_msgs::msg::Header& _header); + + /*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ + eProsima_user_DllExport void header(std_msgs::msg::Header&& _header); + + /*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ + eProsima_user_DllExport const std_msgs::msg::Header& header() const; + + /*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ + eProsima_user_DllExport std_msgs::msg::Header& header(); + /*! + * @brief This function copies the value in member orientation + * @param _orientation New value to be copied in member orientation + */ + eProsima_user_DllExport void orientation(const geometry_msgs::msg::Quaternion& _orientation); + + /*! + * @brief This function moves the value in member orientation + * @param _orientation New value to be moved in member orientation + */ + eProsima_user_DllExport void orientation(geometry_msgs::msg::Quaternion&& _orientation); + + /*! + * @brief This function returns a constant reference to member orientation + * @return Constant reference to member orientation + */ + eProsima_user_DllExport const geometry_msgs::msg::Quaternion& orientation() const; + + /*! + * @brief This function returns a reference to member orientation + * @return Reference to member orientation + */ + eProsima_user_DllExport geometry_msgs::msg::Quaternion& orientation(); + /*! + * @brief This function copies the value in member orientation_covariance + * @param _orientation_covariance New value to be copied in member orientation_covariance + */ + eProsima_user_DllExport void orientation_covariance( + const sensor_msgs::msg::sensor_msgs__Imu__double_array_9& _orientation_covariance); + + /*! + * @brief This function moves the value in member orientation_covariance + * @param _orientation_covariance New value to be moved in member orientation_covariance + */ + eProsima_user_DllExport void orientation_covariance( + sensor_msgs::msg::sensor_msgs__Imu__double_array_9&& _orientation_covariance); + + /*! + * @brief This function returns a constant reference to member orientation_covariance + * @return Constant reference to member orientation_covariance + */ + eProsima_user_DllExport const sensor_msgs::msg::sensor_msgs__Imu__double_array_9& orientation_covariance() const; + + /*! + * @brief This function returns a reference to member orientation_covariance + * @return Reference to member orientation_covariance + */ + eProsima_user_DllExport sensor_msgs::msg::sensor_msgs__Imu__double_array_9& orientation_covariance(); + /*! + * @brief This function copies the value in member angular_velocity + * @param _angular_velocity New value to be copied in member angular_velocity + */ + eProsima_user_DllExport void angular_velocity(const geometry_msgs::msg::Vector3& _angular_velocity); + + /*! + * @brief This function moves the value in member angular_velocity + * @param _angular_velocity New value to be moved in member angular_velocity + */ + eProsima_user_DllExport void angular_velocity(geometry_msgs::msg::Vector3&& _angular_velocity); + + /*! + * @brief This function returns a constant reference to member angular_velocity + * @return Constant reference to member angular_velocity + */ + eProsima_user_DllExport const geometry_msgs::msg::Vector3& angular_velocity() const; + + /*! + * @brief This function returns a reference to member angular_velocity + * @return Reference to member angular_velocity + */ + eProsima_user_DllExport geometry_msgs::msg::Vector3& angular_velocity(); + /*! + * @brief This function copies the value in member angular_velocity_covariance + * @param _angular_velocity_covariance New value to be copied in member angular_velocity_covariance + */ + eProsima_user_DllExport void angular_velocity_covariance( + const sensor_msgs::msg::sensor_msgs__Imu__double_array_9& _angular_velocity_covariance); + + /*! + * @brief This function moves the value in member angular_velocity_covariance + * @param _angular_velocity_covariance New value to be moved in member angular_velocity_covariance + */ + eProsima_user_DllExport void angular_velocity_covariance( + sensor_msgs::msg::sensor_msgs__Imu__double_array_9&& _angular_velocity_covariance); + + /*! + * @brief This function returns a constant reference to member angular_velocity_covariance + * @return Constant reference to member angular_velocity_covariance + */ + eProsima_user_DllExport const sensor_msgs::msg::sensor_msgs__Imu__double_array_9& angular_velocity_covariance() const; + + /*! + * @brief This function returns a reference to member angular_velocity_covariance + * @return Reference to member angular_velocity_covariance + */ + eProsima_user_DllExport sensor_msgs::msg::sensor_msgs__Imu__double_array_9& angular_velocity_covariance(); + /*! + * @brief This function copies the value in member linear_acceleration + * @param _linear_acceleration New value to be copied in member linear_acceleration + */ + eProsima_user_DllExport void linear_acceleration(const geometry_msgs::msg::Vector3& _linear_acceleration); + + /*! + * @brief This function moves the value in member linear_acceleration + * @param _linear_acceleration New value to be moved in member linear_acceleration + */ + eProsima_user_DllExport void linear_acceleration(geometry_msgs::msg::Vector3&& _linear_acceleration); + + /*! + * @brief This function returns a constant reference to member linear_acceleration + * @return Constant reference to member linear_acceleration + */ + eProsima_user_DllExport const geometry_msgs::msg::Vector3& linear_acceleration() const; + + /*! + * @brief This function returns a reference to member linear_acceleration + * @return Reference to member linear_acceleration + */ + eProsima_user_DllExport geometry_msgs::msg::Vector3& linear_acceleration(); + /*! + * @brief This function copies the value in member linear_acceleration_covariance + * @param _linear_acceleration_covariance New value to be copied in member linear_acceleration_covariance + */ + eProsima_user_DllExport void linear_acceleration_covariance( + const sensor_msgs::msg::sensor_msgs__Imu__double_array_9& _linear_acceleration_covariance); + + /*! + * @brief This function moves the value in member linear_acceleration_covariance + * @param _linear_acceleration_covariance New value to be moved in member linear_acceleration_covariance + */ + eProsima_user_DllExport void linear_acceleration_covariance( + sensor_msgs::msg::sensor_msgs__Imu__double_array_9&& _linear_acceleration_covariance); + + /*! + * @brief This function returns a constant reference to member linear_acceleration_covariance + * @return Constant reference to member linear_acceleration_covariance + */ + eProsima_user_DllExport const sensor_msgs::msg::sensor_msgs__Imu__double_array_9& linear_acceleration_covariance() + const; + + /*! + * @brief This function returns a reference to member linear_acceleration_covariance + * @return Reference to member linear_acceleration_covariance + */ + eProsima_user_DllExport sensor_msgs::msg::sensor_msgs__Imu__double_array_9& linear_acceleration_covariance(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const sensor_msgs::msg::Imu& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + std_msgs::msg::Header m_header; + geometry_msgs::msg::Quaternion m_orientation; + sensor_msgs::msg::sensor_msgs__Imu__double_array_9 m_orientation_covariance; + geometry_msgs::msg::Vector3 m_angular_velocity; + sensor_msgs::msg::sensor_msgs__Imu__double_array_9 m_angular_velocity_covariance; + geometry_msgs::msg::Vector3 m_linear_acceleration; + sensor_msgs::msg::sensor_msgs__Imu__double_array_9 m_linear_acceleration_covariance; +}; +} // namespace msg +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMU_H_ diff --git a/LibCarla/source/carla/ros2/types/ImuPubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImuPubSubTypes.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/ImuPubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImuPubSubTypes.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImuPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImuPubSubTypes.h new file mode 100644 index 00000000000..b4ecc2150df --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImuPubSubTypes.h @@ -0,0 +1,96 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file ImuPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMU_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMU_PUBSUBTYPES_H_ + +#include +#include + +#include "Imu.h" + +#include "geometry_msgs/msg/QuaternionPubSubTypes.h" +#include "geometry_msgs/msg/Vector3PubSubTypes.h" +#include "std_msgs/msg/HeaderPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated Imu is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace sensor_msgs { +namespace msg { +typedef std::array sensor_msgs__Imu__double_array_9; + +/*! + * @brief This class represents the TopicDataType of the type Imu defined by the user in the IDL file. + * @ingroup IMU + */ +class ImuPubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef Imu type; + + eProsima_user_DllExport ImuPubSubType(); + + eProsima_user_DllExport virtual ~ImuPubSubType() override; + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + (void)memory; + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; + unsigned char* m_keyBuffer; +}; +} // namespace msg +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMU_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/NavSatFix.cpp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFix.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/NavSatFix.cpp rename to LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFix.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFix.h b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFix.h new file mode 100644 index 00000000000..64985f357b4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFix.h @@ -0,0 +1,329 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file NavSatFix.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIX_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIX_H_ + +#include "NavSatStatus.h" +#include "std_msgs/msg/Header.h" + +#include + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(NavSatFix_SOURCE) +#define NavSatFix_DllAPI __declspec(dllexport) +#else +#define NavSatFix_DllAPI __declspec(dllimport) +#endif // NavSatFix_SOURCE +#else +#define NavSatFix_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define NavSatFix_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace sensor_msgs { +namespace msg { +const uint8_t NavSatFix__COVARIANCE_TYPE_UNKNOWN = 0; +const uint8_t NavSatFix__COVARIANCE_TYPE_APPROXIMATED = 1; +const uint8_t NavSatFix__COVARIANCE_TYPE_DIAGONAL_KNOWN = 2; +const uint8_t NavSatFix__COVARIANCE_TYPE_KNOWN = 3; +typedef std::array sensor_msgs__NavSatFix__double_array_9; +/*! + * @brief This class represents the structure NavSatFix defined by the user in the IDL file. + * @ingroup NAVSATFIX + */ +class NavSatFix { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport NavSatFix(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~NavSatFix(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object sensor_msgs::msg::NavSatFix that will be copied. + */ + eProsima_user_DllExport NavSatFix(const NavSatFix& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object sensor_msgs::msg::NavSatFix that will be copied. + */ + eProsima_user_DllExport NavSatFix(NavSatFix&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object sensor_msgs::msg::NavSatFix that will be copied. + */ + eProsima_user_DllExport NavSatFix& operator=(const NavSatFix& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object sensor_msgs::msg::NavSatFix that will be copied. + */ + eProsima_user_DllExport NavSatFix& operator=(NavSatFix&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x sensor_msgs::msg::NavSatFix object to compare. + */ + eProsima_user_DllExport bool operator==(const NavSatFix& x) const; + + /*! + * @brief Comparison operator. + * @param x sensor_msgs::msg::NavSatFix object to compare. + */ + eProsima_user_DllExport bool operator!=(const NavSatFix& x) const; + + /*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ + eProsima_user_DllExport void header(const std_msgs::msg::Header& _header); + + /*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ + eProsima_user_DllExport void header(std_msgs::msg::Header&& _header); + + /*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ + eProsima_user_DllExport const std_msgs::msg::Header& header() const; + + /*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ + eProsima_user_DllExport std_msgs::msg::Header& header(); + /*! + * @brief This function copies the value in member status + * @param _status New value to be copied in member status + */ + eProsima_user_DllExport void status(const sensor_msgs::msg::NavSatStatus& _status); + + /*! + * @brief This function moves the value in member status + * @param _status New value to be moved in member status + */ + eProsima_user_DllExport void status(sensor_msgs::msg::NavSatStatus&& _status); + + /*! + * @brief This function returns a constant reference to member status + * @return Constant reference to member status + */ + eProsima_user_DllExport const sensor_msgs::msg::NavSatStatus& status() const; + + /*! + * @brief This function returns a reference to member status + * @return Reference to member status + */ + eProsima_user_DllExport sensor_msgs::msg::NavSatStatus& status(); + /*! + * @brief This function sets a value in member latitude + * @param _latitude New value for member latitude + */ + eProsima_user_DllExport void latitude(double _latitude); + + /*! + * @brief This function returns the value of member latitude + * @return Value of member latitude + */ + eProsima_user_DllExport double latitude() const; + + /*! + * @brief This function returns a reference to member latitude + * @return Reference to member latitude + */ + eProsima_user_DllExport double& latitude(); + + /*! + * @brief This function sets a value in member longitude + * @param _longitude New value for member longitude + */ + eProsima_user_DllExport void longitude(double _longitude); + + /*! + * @brief This function returns the value of member longitude + * @return Value of member longitude + */ + eProsima_user_DllExport double longitude() const; + + /*! + * @brief This function returns a reference to member longitude + * @return Reference to member longitude + */ + eProsima_user_DllExport double& longitude(); + + /*! + * @brief This function sets a value in member altitude + * @param _altitude New value for member altitude + */ + eProsima_user_DllExport void altitude(double _altitude); + + /*! + * @brief This function returns the value of member altitude + * @return Value of member altitude + */ + eProsima_user_DllExport double altitude() const; + + /*! + * @brief This function returns a reference to member altitude + * @return Reference to member altitude + */ + eProsima_user_DllExport double& altitude(); + + /*! + * @brief This function copies the value in member position_covariance + * @param _position_covariance New value to be copied in member position_covariance + */ + eProsima_user_DllExport void position_covariance( + const sensor_msgs::msg::sensor_msgs__NavSatFix__double_array_9& _position_covariance); + + /*! + * @brief This function moves the value in member position_covariance + * @param _position_covariance New value to be moved in member position_covariance + */ + eProsima_user_DllExport void position_covariance( + sensor_msgs::msg::sensor_msgs__NavSatFix__double_array_9&& _position_covariance); + + /*! + * @brief This function returns a constant reference to member position_covariance + * @return Constant reference to member position_covariance + */ + eProsima_user_DllExport const sensor_msgs::msg::sensor_msgs__NavSatFix__double_array_9& position_covariance() const; + + /*! + * @brief This function returns a reference to member position_covariance + * @return Reference to member position_covariance + */ + eProsima_user_DllExport sensor_msgs::msg::sensor_msgs__NavSatFix__double_array_9& position_covariance(); + /*! + * @brief This function sets a value in member position_covariance_type + * @param _position_covariance_type New value for member position_covariance_type + */ + eProsima_user_DllExport void position_covariance_type(uint8_t _position_covariance_type); + + /*! + * @brief This function returns the value of member position_covariance_type + * @return Value of member position_covariance_type + */ + eProsima_user_DllExport uint8_t position_covariance_type() const; + + /*! + * @brief This function returns a reference to member position_covariance_type + * @return Reference to member position_covariance_type + */ + eProsima_user_DllExport uint8_t& position_covariance_type(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const sensor_msgs::msg::NavSatFix& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + std_msgs::msg::Header m_header; + sensor_msgs::msg::NavSatStatus m_status; + double m_latitude; + double m_longitude; + double m_altitude; + sensor_msgs::msg::sensor_msgs__NavSatFix__double_array_9 m_position_covariance; + uint8_t m_position_covariance_type; +}; +} // namespace msg +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIX_H_ diff --git a/LibCarla/source/carla/ros2/types/NavSatFixPubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFixPubSubTypes.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/NavSatFixPubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFixPubSubTypes.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFixPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFixPubSubTypes.h new file mode 100644 index 00000000000..5a41522e6e1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFixPubSubTypes.h @@ -0,0 +1,95 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file NavSatFixPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIX_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIX_PUBSUBTYPES_H_ + +#include +#include + +#include "NavSatFix.h" + +#include "NavSatStatusPubSubTypes.h" +#include "std_msgs/msg/HeaderPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated NavSatFix is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace sensor_msgs { +namespace msg { +typedef std::array sensor_msgs__NavSatFix__double_array_9; + +/*! + * @brief This class represents the TopicDataType of the type NavSatFix defined by the user in the IDL file. + * @ingroup NAVSATFIX + */ +class NavSatFixPubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef NavSatFix type; + + eProsima_user_DllExport NavSatFixPubSubType(); + + eProsima_user_DllExport virtual ~NavSatFixPubSubType() override; + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + (void)memory; + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; + unsigned char* m_keyBuffer; +}; +} // namespace msg +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIX_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/NavSatStatus.cpp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatus.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/NavSatStatus.cpp rename to LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatus.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatus.h b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatus.h new file mode 100644 index 00000000000..183499cf74c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatus.h @@ -0,0 +1,217 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file NavSatStatus.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUS_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUS_H_ + +#include + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(NavSatStatus_SOURCE) +#define NavSatStatus_DllAPI __declspec(dllexport) +#else +#define NavSatStatus_DllAPI __declspec(dllimport) +#endif // NavSatStatus_SOURCE +#else +#define NavSatStatus_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define NavSatStatus_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace sensor_msgs { +namespace msg { +const uint8_t NavSatStatus__STATUS_NO_FIX = 255; +const uint8_t NavSatStatus__STATUS_FIX = 0; +const uint8_t NavSatStatus__STATUS_SBAS_FIX = 1; +const uint8_t NavSatStatus__STATUS_GBAS_FIX = 2; +const uint16_t NavSatStatus__SERVICE_GPS = 1; +const uint16_t NavSatStatus__SERVICE_GLONASS = 2; +const uint16_t NavSatStatus__SERVICE_COMPASS = 4; +const uint16_t NavSatStatus__SERVICE_GALILEO = 8; +/*! + * @brief This class represents the structure NavSatStatus defined by the user in the IDL file. + * @ingroup NAVSATSTATUS + */ +class NavSatStatus { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport NavSatStatus(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~NavSatStatus(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object sensor_msgs::msg::NavSatStatus that will be copied. + */ + eProsima_user_DllExport NavSatStatus(const NavSatStatus& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object sensor_msgs::msg::NavSatStatus that will be copied. + */ + eProsima_user_DllExport NavSatStatus(NavSatStatus&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object sensor_msgs::msg::NavSatStatus that will be copied. + */ + eProsima_user_DllExport NavSatStatus& operator=(const NavSatStatus& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object sensor_msgs::msg::NavSatStatus that will be copied. + */ + eProsima_user_DllExport NavSatStatus& operator=(NavSatStatus&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x sensor_msgs::msg::NavSatStatus object to compare. + */ + eProsima_user_DllExport bool operator==(const NavSatStatus& x) const; + + /*! + * @brief Comparison operator. + * @param x sensor_msgs::msg::NavSatStatus object to compare. + */ + eProsima_user_DllExport bool operator!=(const NavSatStatus& x) const; + + /*! + * @brief This function sets a value in member status + * @param _status New value for member status + */ + eProsima_user_DllExport void status(uint8_t _status); + + /*! + * @brief This function returns the value of member status + * @return Value of member status + */ + eProsima_user_DllExport uint8_t status() const; + + /*! + * @brief This function returns a reference to member status + * @return Reference to member status + */ + eProsima_user_DllExport uint8_t& status(); + + /*! + * @brief This function sets a value in member service + * @param _service New value for member service + */ + eProsima_user_DllExport void service(uint16_t _service); + + /*! + * @brief This function returns the value of member service + * @return Value of member service + */ + eProsima_user_DllExport uint16_t service() const; + + /*! + * @brief This function returns a reference to member service + * @return Reference to member service + */ + eProsima_user_DllExport uint16_t& service(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const sensor_msgs::msg::NavSatStatus& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + uint8_t m_status; + uint16_t m_service; +}; +} // namespace msg +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUS_H_ diff --git a/LibCarla/source/carla/ros2/types/NavSatStatusPubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatusPubSubTypes.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/NavSatStatusPubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatusPubSubTypes.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatusPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatusPubSubTypes.h new file mode 100644 index 00000000000..ec4276146a3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatusPubSubTypes.h @@ -0,0 +1,119 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file NavSatStatusPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUS_PUBSUBTYPES_H_ + +#include +#include + +#include "NavSatStatus.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated NavSatStatus is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace sensor_msgs { +namespace msg { +#ifndef SWIG +namespace detail { + +template +struct NavSatStatus_rob { + friend constexpr typename Tag::type get(Tag) { + return M; + } +}; + +struct NavSatStatus_f { + typedef uint16_t NavSatStatus::*type; + friend constexpr type get(NavSatStatus_f); +}; + +template struct NavSatStatus_rob; + +template +inline size_t constexpr NavSatStatus_offset_of() { + return ((::size_t) & reinterpret_cast((((T*)0)->*get(Tag())))); +} +} // namespace detail +#endif + +/*! + * @brief This class represents the TopicDataType of the type NavSatStatus defined by the user in the IDL file. + * @ingroup NAVSATSTATUS + */ +class NavSatStatusPubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef NavSatStatus type; + + eProsima_user_DllExport NavSatStatusPubSubType(); + + eProsima_user_DllExport virtual ~NavSatStatusPubSubType() override; + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return true; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return is_plain_impl(); + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + new (memory) NavSatStatus(); + return true; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; + unsigned char* m_keyBuffer; + +private: + static constexpr bool is_plain_impl() { + return 4ULL == (detail::NavSatStatus_offset_of() + sizeof(uint16_t)); + } +}; +} // namespace msg +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUS_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2.cc b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2.cc new file mode 100644 index 00000000000..27919c778b1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2.cc @@ -0,0 +1,487 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PointCloud2.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "PointCloud2.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + +#define sensor_msgs_msg_PointField_max_cdr_typesize 272ULL; +#define std_msgs_msg_Time_max_cdr_typesize 8ULL; +#define sensor_msgs_msg_PointCloud2_max_cdr_typesize 27597ULL; +#define std_msgs_msg_Header_max_cdr_typesize 268ULL; +#define sensor_msgs_msg_PointField_max_key_cdr_typesize 0ULL; +#define std_msgs_msg_Time_max_key_cdr_typesize 0ULL; +#define sensor_msgs_msg_PointCloud2_max_key_cdr_typesize 0ULL; +#define std_msgs_msg_Header_max_key_cdr_typesize 0ULL; + +template +sensor_msgs::msg::PointCloud2T::PointCloud2T() { + // std_msgs::msg::Header m_header + + // unsigned long m_height + m_height = 0; + // unsigned long m_width + m_width = 0; + // sequence m_fields + + // boolean m_is_bigendian + m_is_bigendian = false; + // unsigned long m_point_step + m_point_step = 0; + // unsigned long m_row_step + m_row_step = 0; + // sequence m_data + + // boolean m_is_dense + m_is_dense = false; +} + +template +sensor_msgs::msg::PointCloud2T::~PointCloud2T() {} + +template +sensor_msgs::msg::PointCloud2T::PointCloud2T(const PointCloud2T& x) { + m_header = x.m_header; + m_height = x.m_height; + m_width = x.m_width; + m_fields = x.m_fields; + m_is_bigendian = x.m_is_bigendian; + m_point_step = x.m_point_step; + m_row_step = x.m_row_step; + m_data = x.m_data; + m_is_dense = x.m_is_dense; +} + +template +sensor_msgs::msg::PointCloud2T::PointCloud2T(PointCloud2T&& x) noexcept { + m_header = std::move(x.m_header); + m_height = x.m_height; + m_width = x.m_width; + m_fields = std::move(x.m_fields); + m_is_bigendian = x.m_is_bigendian; + m_point_step = x.m_point_step; + m_row_step = x.m_row_step; + m_data = std::move(x.m_data); + m_is_dense = x.m_is_dense; +} + +template +sensor_msgs::msg::PointCloud2T& sensor_msgs::msg::PointCloud2T::operator=( + const PointCloud2T& x) { + m_header = x.m_header; + m_height = x.m_height; + m_width = x.m_width; + m_fields = x.m_fields; + m_is_bigendian = x.m_is_bigendian; + m_point_step = x.m_point_step; + m_row_step = x.m_row_step; + m_data = x.m_data; + m_is_dense = x.m_is_dense; + + return *this; +} + +template +sensor_msgs::msg::PointCloud2T& sensor_msgs::msg::PointCloud2T::operator=( + PointCloud2T&& x) noexcept { + m_header = std::move(x.m_header); + m_height = x.m_height; + m_width = x.m_width; + m_fields = std::move(x.m_fields); + m_is_bigendian = x.m_is_bigendian; + m_point_step = x.m_point_step; + m_row_step = x.m_row_step; + m_data = std::move(x.m_data); + m_is_dense = x.m_is_dense; + + return *this; +} + +template +bool sensor_msgs::msg::PointCloud2T::operator==(const PointCloud2T& x) const { + return (m_header == x.m_header && m_height == x.m_height && m_width == x.m_width && m_fields == x.m_fields && + m_is_bigendian == x.m_is_bigendian && m_point_step == x.m_point_step && m_row_step == x.m_row_step && + m_data == x.m_data && m_is_dense == x.m_is_dense); +} + +template +bool sensor_msgs::msg::PointCloud2T::operator!=(const PointCloud2T& x) const { + return !(*this == x); +} + +template +size_t sensor_msgs::msg::PointCloud2T::getMaxCdrSerializedSize(size_t current_alignment) { + static_cast(current_alignment); + return sensor_msgs_msg_PointCloud2_max_cdr_typesize; +} + +template +size_t sensor_msgs::msg::PointCloud2T::getCdrSerializedSize( + const sensor_msgs::msg::PointCloud2T& data, size_t current_alignment) { + size_t initial_alignment = current_alignment; + current_alignment += std_msgs::msg::Header::getCdrSerializedSize(data.header(), current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + for (size_t a = 0; a < data.fields().size(); ++a) { + current_alignment += sensor_msgs::msg::PointField::getCdrSerializedSize(data.fields().at(a), current_alignment); + } + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + if (data.data().size() > 0) { + current_alignment += (data.data().size() * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + } + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + return current_alignment - initial_alignment; +} + +template +void sensor_msgs::msg::PointCloud2T::serialize(eprosima::fastcdr::Cdr& scdr) const { + scdr << m_header; + scdr << m_height; + scdr << m_width; + scdr << m_fields; + scdr << m_is_bigendian; + scdr << m_point_step; + scdr << m_row_step; + scdr << m_data; + scdr << m_is_dense; +} + +template +void sensor_msgs::msg::PointCloud2T::deserialize(eprosima::fastcdr::Cdr& dcdr) { + dcdr >> m_header; + dcdr >> m_height; + dcdr >> m_width; + dcdr >> m_fields; + dcdr >> m_is_bigendian; + dcdr >> m_point_step; + dcdr >> m_row_step; + dcdr >> m_data; + dcdr >> m_is_dense; +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +template +void sensor_msgs::msg::PointCloud2T::header(const std_msgs::msg::Header& _header) { + m_header = _header; +} + +/*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ +template +void sensor_msgs::msg::PointCloud2T::header(std_msgs::msg::Header&& _header) { + m_header = std::move(_header); +} + +/*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ +template +const std_msgs::msg::Header& sensor_msgs::msg::PointCloud2T::header() const { + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +template +std_msgs::msg::Header& sensor_msgs::msg::PointCloud2T::header() { + return m_header; +} + +/*! + * @brief This function sets a value in member height + * @param _height New value for member height + */ +template +void sensor_msgs::msg::PointCloud2T::height(uint32_t _height) { + m_height = _height; +} + +/*! + * @brief This function returns the value of member height + * @return Value of member height + */ +template +uint32_t sensor_msgs::msg::PointCloud2T::height() const { + return m_height; +} + +/*! + * @brief This function returns a reference to member height + * @return Reference to member height + */ +template +uint32_t& sensor_msgs::msg::PointCloud2T::height() { + return m_height; +} + +/*! + * @brief This function sets a value in member width + * @param _width New value for member width + */ +template +void sensor_msgs::msg::PointCloud2T::width(uint32_t _width) { + m_width = _width; +} + +/*! + * @brief This function returns the value of member width + * @return Value of member width + */ +template +uint32_t sensor_msgs::msg::PointCloud2T::width() const { + return m_width; +} + +/*! + * @brief This function returns a reference to member width + * @return Reference to member width + */ +template +uint32_t& sensor_msgs::msg::PointCloud2T::width() { + return m_width; +} + +/*! + * @brief This function copies the value in member fields + * @param _fields New value to be copied in member fields + */ +template +void sensor_msgs::msg::PointCloud2T::fields(const std::vector& _fields) { + m_fields = _fields; +} + +/*! + * @brief This function moves the value in member fields + * @param _fields New value to be moved in member fields + */ +template +void sensor_msgs::msg::PointCloud2T::fields(std::vector&& _fields) { + m_fields = std::move(_fields); +} + +/*! + * @brief This function returns a constant reference to member fields + * @return Constant reference to member fields + */ +template +const std::vector& sensor_msgs::msg::PointCloud2T::fields() const { + return m_fields; +} + +/*! + * @brief This function returns a reference to member fields + * @return Reference to member fields + */ +template +std::vector& sensor_msgs::msg::PointCloud2T::fields() { + return m_fields; +} + +/*! + * @brief This function sets a value in member is_bigendian + * @param _is_bigendian New value for member is_bigendian + */ +template +void sensor_msgs::msg::PointCloud2T::is_bigendian(bool _is_bigendian) { + m_is_bigendian = _is_bigendian; +} + +/*! + * @brief This function returns the value of member is_bigendian + * @return Value of member is_bigendian + */ +template +bool sensor_msgs::msg::PointCloud2T::is_bigendian() const { + return m_is_bigendian; +} + +/*! + * @brief This function returns a reference to member is_bigendian + * @return Reference to member is_bigendian + */ +template +bool& sensor_msgs::msg::PointCloud2T::is_bigendian() { + return m_is_bigendian; +} + +/*! + * @brief This function sets a value in member point_step + * @param _point_step New value for member point_step + */ +template +void sensor_msgs::msg::PointCloud2T::point_step(uint32_t _point_step) { + m_point_step = _point_step; +} + +/*! + * @brief This function returns the value of member point_step + * @return Value of member point_step + */ +template +uint32_t sensor_msgs::msg::PointCloud2T::point_step() const { + return m_point_step; +} + +/*! + * @brief This function returns a reference to member point_step + * @return Reference to member point_step + */ +template +uint32_t& sensor_msgs::msg::PointCloud2T::point_step() { + return m_point_step; +} + +/*! + * @brief This function sets a value in member row_step + * @param _row_step New value for member row_step + */ +template +void sensor_msgs::msg::PointCloud2T::row_step(uint32_t _row_step) { + m_row_step = _row_step; +} + +/*! + * @brief This function returns the value of member row_step + * @return Value of member row_step + */ +template +uint32_t sensor_msgs::msg::PointCloud2T::row_step() const { + return m_row_step; +} + +/*! + * @brief This function returns a reference to member row_step + * @return Reference to member row_step + */ +template +uint32_t& sensor_msgs::msg::PointCloud2T::row_step() { + return m_row_step; +} + +/*! + * @brief This function copies the value in member data + * @param _data New value to be copied in member data + */ +template +void sensor_msgs::msg::PointCloud2T::data( + const typename sensor_msgs::msg::PointCloud2T::vector_type& _data) { + m_data = _data; +} + +/*! + * @brief This function moves the value in member data + * @param _data New value to be moved in member data + */ +template +void sensor_msgs::msg::PointCloud2T::data( + typename sensor_msgs::msg::PointCloud2T::vector_type&& _data) { + m_data = std::move(_data); +} + +/*! + * @brief This function returns a constant reference to member data + * @return Constant reference to member data + */ +template +const typename sensor_msgs::msg::PointCloud2T::vector_type& sensor_msgs::msg::PointCloud2T::data() + const { + return m_data; +} + +/*! + * @brief This function returns a reference to member data + * @return Reference to member data + */ +template +typename sensor_msgs::msg::PointCloud2T::vector_type& sensor_msgs::msg::PointCloud2T::data() { + return m_data; +} + +/*! + * @brief This function sets a value in member is_dense + * @param _is_dense New value for member is_dense + */ +template +void sensor_msgs::msg::PointCloud2T::is_dense(bool _is_dense) { + m_is_dense = _is_dense; +} + +/*! + * @brief This function returns the value of member is_dense + * @return Value of member is_dense + */ +template +bool sensor_msgs::msg::PointCloud2T::is_dense() const { + return m_is_dense; +} + +/*! + * @brief This function returns a reference to member is_dense + * @return Reference to member is_dense + */ +template +bool& sensor_msgs::msg::PointCloud2T::is_dense() { + return m_is_dense; +} + +template +size_t sensor_msgs::msg::PointCloud2T::getKeyMaxCdrSerializedSize(size_t current_alignment) { + static_cast(current_alignment); + return sensor_msgs_msg_PointCloud2_max_key_cdr_typesize; +} + +template +bool sensor_msgs::msg::PointCloud2T::isKeyDefined() { + return false; +} + +template +void sensor_msgs::msg::PointCloud2T::serializeKey(eprosima::fastcdr::Cdr& scdr) const { + (void)scdr; +} diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2.h b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2.h new file mode 100644 index 00000000000..2cbfba0f4f3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2.h @@ -0,0 +1,372 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PointCloud2.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2_H_ + +#include "PointField.h" +#include "std_msgs/msg/Header.h" + +#include + +#include +#include +#include +#include +#include +#include + +#include "carla/sensor/data/SerializerVectorAllocator.h" + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(PointCloud2_SOURCE) +#define PointCloud2_DllAPI __declspec(dllexport) +#else +#define PointCloud2_DllAPI __declspec(dllimport) +#endif // PointCloud2_SOURCE +#else +#define PointCloud2_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define PointCloud2_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace sensor_msgs { +namespace msg { +/*! + * @brief This class represents the structure PointCloud2T defined by the user in the IDL file. + * @ingroup POINTCLOUD2 + */ +template +class PointCloud2T { +public: + using base_type = uint8_t; + using allocator_type = ALLOCATOR; + using vector_type = std::vector; + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport PointCloud2T(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~PointCloud2T(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object sensor_msgs::msg::PointCloud2T that will be copied. + */ + eProsima_user_DllExport PointCloud2T(const PointCloud2T& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object sensor_msgs::msg::PointCloud2T that will be copied. + */ + eProsima_user_DllExport PointCloud2T(PointCloud2T&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object sensor_msgs::msg::PointCloud2T that will be copied. + */ + eProsima_user_DllExport PointCloud2T& operator=(const PointCloud2T& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object sensor_msgs::msg::PointCloud2T that will be copied. + */ + eProsima_user_DllExport PointCloud2T& operator=(PointCloud2T&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x sensor_msgs::msg::PointCloud2T object to compare. + */ + eProsima_user_DllExport bool operator==(const PointCloud2T& x) const; + + /*! + * @brief Comparison operator. + * @param x sensor_msgs::msg::PointCloud2T object to compare. + */ + eProsima_user_DllExport bool operator!=(const PointCloud2T& x) const; + + /*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ + eProsima_user_DllExport void header(const std_msgs::msg::Header& _header); + + /*! + * @brief This function moves the value in member header + * @param _header New value to be moved in member header + */ + eProsima_user_DllExport void header(std_msgs::msg::Header&& _header); + + /*! + * @brief This function returns a constant reference to member header + * @return Constant reference to member header + */ + eProsima_user_DllExport const std_msgs::msg::Header& header() const; + + /*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ + eProsima_user_DllExport std_msgs::msg::Header& header(); + /*! + * @brief This function sets a value in member height + * @param _height New value for member height + */ + eProsima_user_DllExport void height(uint32_t _height); + + /*! + * @brief This function returns the value of member height + * @return Value of member height + */ + eProsima_user_DllExport uint32_t height() const; + + /*! + * @brief This function returns a reference to member height + * @return Reference to member height + */ + eProsima_user_DllExport uint32_t& height(); + + /*! + * @brief This function sets a value in member width + * @param _width New value for member width + */ + eProsima_user_DllExport void width(uint32_t _width); + + /*! + * @brief This function returns the value of member width + * @return Value of member width + */ + eProsima_user_DllExport uint32_t width() const; + + /*! + * @brief This function returns a reference to member width + * @return Reference to member width + */ + eProsima_user_DllExport uint32_t& width(); + + /*! + * @brief This function copies the value in member fields + * @param _fields New value to be copied in member fields + */ + eProsima_user_DllExport void fields(const std::vector& _fields); + + /*! + * @brief This function moves the value in member fields + * @param _fields New value to be moved in member fields + */ + eProsima_user_DllExport void fields(std::vector&& _fields); + + /*! + * @brief This function returns a constant reference to member fields + * @return Constant reference to member fields + */ + eProsima_user_DllExport const std::vector& fields() const; + + /*! + * @brief This function returns a reference to member fields + * @return Reference to member fields + */ + eProsima_user_DllExport std::vector& fields(); + /*! + * @brief This function sets a value in member is_bigendian + * @param _is_bigendian New value for member is_bigendian + */ + eProsima_user_DllExport void is_bigendian(bool _is_bigendian); + + /*! + * @brief This function returns the value of member is_bigendian + * @return Value of member is_bigendian + */ + eProsima_user_DllExport bool is_bigendian() const; + + /*! + * @brief This function returns a reference to member is_bigendian + * @return Reference to member is_bigendian + */ + eProsima_user_DllExport bool& is_bigendian(); + + /*! + * @brief This function sets a value in member point_step + * @param _point_step New value for member point_step + */ + eProsima_user_DllExport void point_step(uint32_t _point_step); + + /*! + * @brief This function returns the value of member point_step + * @return Value of member point_step + */ + eProsima_user_DllExport uint32_t point_step() const; + + /*! + * @brief This function returns a reference to member point_step + * @return Reference to member point_step + */ + eProsima_user_DllExport uint32_t& point_step(); + + /*! + * @brief This function sets a value in member row_step + * @param _row_step New value for member row_step + */ + eProsima_user_DllExport void row_step(uint32_t _row_step); + + /*! + * @brief This function returns the value of member row_step + * @return Value of member row_step + */ + eProsima_user_DllExport uint32_t row_step() const; + + /*! + * @brief This function returns a reference to member row_step + * @return Reference to member row_step + */ + eProsima_user_DllExport uint32_t& row_step(); + + /*! + * @brief This function copies the value in member data + * @param _data New value to be copied in member data + */ + eProsima_user_DllExport void data(const vector_type& _data); + + /*! + * @brief This function moves the value in member data + * @param _data New value to be moved in member data + */ + eProsima_user_DllExport void data(vector_type&& _data); + + /*! + * @brief This function returns a constant reference to member data + * @return Constant reference to member data + */ + eProsima_user_DllExport const vector_type& data() const; + + /*! + * @brief This function returns a reference to member data + * @return Reference to member data + */ + eProsima_user_DllExport vector_type& data(); + /*! + * @brief This function sets a value in member is_dense + * @param _is_dense New value for member is_dense + */ + eProsima_user_DllExport void is_dense(bool _is_dense); + + /*! + * @brief This function returns the value of member is_dense + * @return Value of member is_dense + */ + eProsima_user_DllExport bool is_dense() const; + + /*! + * @brief This function returns a reference to member is_dense + * @return Reference to member is_dense + */ + eProsima_user_DllExport bool& is_dense(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const sensor_msgs::msg::PointCloud2T& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + std_msgs::msg::Header m_header; + uint32_t m_height; + uint32_t m_width; + std::vector m_fields; + bool m_is_bigendian; + uint32_t m_point_step; + uint32_t m_row_step; + vector_type m_data; + bool m_is_dense; +}; + +using PointCloud2 = PointCloud2T>; + +} // namespace msg +} // namespace sensor_msgs + +#include "PointCloud2.cc" + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2_H_ diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2PubSubTypes.cc b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2PubSubTypes.cc new file mode 100644 index 00000000000..3ed3d81e7f2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2PubSubTypes.cc @@ -0,0 +1,150 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PointCloud2PubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#include +#include + +#include "PointCloud2PubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace sensor_msgs { +namespace msg { +template +PointCloud2PubSubTypeT::PointCloud2PubSubTypeT() { + setName("sensor_msgs::msg::dds_::PointCloud2_"); + auto type_size = PointCloud2T::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = PointCloud2T::isKeyDefined(); + size_t keyLength = PointCloud2T::getKeyMaxCdrSerializedSize() > 16 + ? PointCloud2T::getKeyMaxCdrSerializedSize() + : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); +} + +template +PointCloud2PubSubTypeT::~PointCloud2PubSubTypeT() { + if (m_keyBuffer != nullptr) { + free(m_keyBuffer); + } +} + +template +bool PointCloud2PubSubTypeT::serialize(void* data, SerializedPayload_t* payload) { + PointCloud2T* p_type = static_cast*>(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try { + // Serialize the object. + p_type->serialize(ser); + } catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; +} + +template +bool PointCloud2PubSubTypeT::deserialize(SerializedPayload_t* payload, void* data) { + try { + // Convert DATA to pointer of your type + PointCloud2T* p_type = static_cast*>(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + p_type->deserialize(deser); + } catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) { + return false; + } + + return true; +} + +template +std::function PointCloud2PubSubTypeT::getSerializedSizeProvider(void* data) { + return [data]() -> uint32_t { + return static_cast(type::getCdrSerializedSize(*static_cast*>(data))) + + 4u /*encapsulation*/; + }; +} + +template +void* PointCloud2PubSubTypeT::createData() { + return reinterpret_cast(new PointCloud2T()); +} + +template +void PointCloud2PubSubTypeT::deleteData(void* data) { + delete (reinterpret_cast*>(data)); +} + +template +bool PointCloud2PubSubTypeT::getKey(void* data, InstanceHandle_t* handle, bool force_md5) { + if (!m_isGetKeyDefined) { + return false; + } + + PointCloud2T* p_type = static_cast*>(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + PointCloud2T::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || PointCloud2T::getKeyMaxCdrSerializedSize() > 16) { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) { + handle->value[i] = m_md5.digest[i]; + } + } else { + for (uint8_t i = 0; i < 16; ++i) { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; +} +} // End of namespace msg +} // End of namespace sensor_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2PubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2PubSubTypes.h new file mode 100644 index 00000000000..bc992c03d29 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2PubSubTypes.h @@ -0,0 +1,99 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PointCloud2PubSubTypeTs.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2_PUBSUBTYPES_H_ + +#include +#include + +#include "PointCloud2.h" + +#include "PointFieldPubSubTypes.h" +#include "std_msgs/msg/HeaderPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated PointCloud2 is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace sensor_msgs { +namespace msg { + +/*! + * @brief This class represents the TopicDataType of the type PointCloud2 defined by the user in the IDL file. + * @ingroup POINTCLOUD2 + */ +template +class PointCloud2PubSubTypeT : public eprosima::fastdds::dds::TopicDataType { +public: + typedef PointCloud2T type; + + eProsima_user_DllExport PointCloud2PubSubTypeT(); + + eProsima_user_DllExport virtual ~PointCloud2PubSubTypeT() override; + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + (void)memory; + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; + unsigned char* m_keyBuffer; +}; + +using PointCloud2PubSubType = PointCloud2PubSubTypeT>; +} // namespace msg +} // namespace sensor_msgs + +#include "PointCloud2PubSubTypes.cc" + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/PointField.cpp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointField.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/PointField.cpp rename to LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointField.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointField.h b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointField.h new file mode 100644 index 00000000000..ba12c86785c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointField.h @@ -0,0 +1,261 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PointField.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELD_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELD_H_ + +#include + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(PointField_SOURCE) +#define PointField_DllAPI __declspec(dllexport) +#else +#define PointField_DllAPI __declspec(dllimport) +#endif // PointField_SOURCE +#else +#define PointField_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define PointField_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace sensor_msgs { +namespace msg { +const uint8_t PointField__INT8 = 1; +const uint8_t PointField__UINT8 = 2; +const uint8_t PointField__INT16 = 3; +const uint8_t PointField__UINT16 = 4; +const uint8_t PointField__INT32 = 5; +const uint8_t PointField__UINT32 = 6; +const uint8_t PointField__FLOAT32 = 7; +const uint8_t PointField__FLOAT64 = 8; + +/*! + * @brief This class represents the structure PointField defined by the user in the IDL file. + * @ingroup POINTFIELD + */ +class PointField { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport PointField(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~PointField(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object sensor_msgs::msg::PointField that will be copied. + */ + eProsima_user_DllExport PointField(const PointField& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object sensor_msgs::msg::PointField that will be copied. + */ + eProsima_user_DllExport PointField(PointField&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object sensor_msgs::msg::PointField that will be copied. + */ + eProsima_user_DllExport PointField& operator=(const PointField& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object sensor_msgs::msg::PointField that will be copied. + */ + eProsima_user_DllExport PointField& operator=(PointField&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x sensor_msgs::msg::PointField object to compare. + */ + eProsima_user_DllExport bool operator==(const PointField& x) const; + + /*! + * @brief Comparison operator. + * @param x sensor_msgs::msg::PointField object to compare. + */ + eProsima_user_DllExport bool operator!=(const PointField& x) const; + + /*! + * @brief This function copies the value in member name + * @param _name New value to be copied in member name + */ + eProsima_user_DllExport void name(const std::string& _name); + + /*! + * @brief This function moves the value in member name + * @param _name New value to be moved in member name + */ + eProsima_user_DllExport void name(std::string&& _name); + + /*! + * @brief This function returns a constant reference to member name + * @return Constant reference to member name + */ + eProsima_user_DllExport const std::string& name() const; + + /*! + * @brief This function returns a reference to member name + * @return Reference to member name + */ + eProsima_user_DllExport std::string& name(); + /*! + * @brief This function sets a value in member offset + * @param _offset New value for member offset + */ + eProsima_user_DllExport void offset(uint32_t _offset); + + /*! + * @brief This function returns the value of member offset + * @return Value of member offset + */ + eProsima_user_DllExport uint32_t offset() const; + + /*! + * @brief This function returns a reference to member offset + * @return Reference to member offset + */ + eProsima_user_DllExport uint32_t& offset(); + + /*! + * @brief This function sets a value in member datatype + * @param _datatype New value for member datatype + */ + eProsima_user_DllExport void datatype(uint8_t _datatype); + + /*! + * @brief This function returns the value of member datatype + * @return Value of member datatype + */ + eProsima_user_DllExport uint8_t datatype() const; + + /*! + * @brief This function returns a reference to member datatype + * @return Reference to member datatype + */ + eProsima_user_DllExport uint8_t& datatype(); + + /*! + * @brief This function sets a value in member count + * @param _count New value for member count + */ + eProsima_user_DllExport void count(uint32_t _count); + + /*! + * @brief This function returns the value of member count + * @return Value of member count + */ + eProsima_user_DllExport uint32_t count() const; + + /*! + * @brief This function returns a reference to member count + * @return Reference to member count + */ + eProsima_user_DllExport uint32_t& count(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const sensor_msgs::msg::PointField& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + std::string m_name; + uint32_t m_offset; + uint8_t m_datatype; + uint32_t m_count; +}; +} // namespace msg +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELD_H_ diff --git a/LibCarla/source/carla/ros2/types/PointFieldPubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointFieldPubSubTypes.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/PointFieldPubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointFieldPubSubTypes.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointFieldPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointFieldPubSubTypes.h new file mode 100644 index 00000000000..f787d0a7080 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointFieldPubSubTypes.h @@ -0,0 +1,90 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file PointFieldPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELD_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELD_PUBSUBTYPES_H_ + +#include +#include + +#include "PointField.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated PointField is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace sensor_msgs { +namespace msg { +/*! + * @brief This class represents the TopicDataType of the type PointField defined by the user in the IDL file. + * @ingroup POINTFIELD + */ +class PointFieldPubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef PointField type; + + eProsima_user_DllExport PointFieldPubSubType(); + + eProsima_user_DllExport virtual ~PointFieldPubSubType() override; + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + (void)memory; + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; + unsigned char* m_keyBuffer; +}; +} // namespace msg +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELD_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/RegionOfInterest.cpp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterest.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/RegionOfInterest.cpp rename to LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterest.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterest.h b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterest.h new file mode 100644 index 00000000000..c36d1ddbafb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterest.h @@ -0,0 +1,266 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file RegionOfInterest.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTEREST_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTEREST_H_ + +#include + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(REGIONOFINTEREST_SOURCE) +#define REGIONOFINTEREST_DllAPI __declspec(dllexport) +#else +#define REGIONOFINTEREST_DllAPI __declspec(dllimport) +#endif // REGIONOFINTEREST_SOURCE +#else +#define REGIONOFINTEREST_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define REGIONOFINTEREST_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace sensor_msgs { +namespace msg { +/*! + * @brief This class represents the structure RegionOfInterest defined by the user in the IDL file. + * @ingroup RegionOfInterest + */ +class RegionOfInterest { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport RegionOfInterest(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~RegionOfInterest(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object sensor_msgs::msg::RegionOfInterest that will be copied. + */ + eProsima_user_DllExport RegionOfInterest(const RegionOfInterest& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object sensor_msgs::msg::RegionOfInterest that will be copied. + */ + eProsima_user_DllExport RegionOfInterest(RegionOfInterest&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object sensor_msgs::msg::RegionOfInterest that will be copied. + */ + eProsima_user_DllExport RegionOfInterest& operator=(const RegionOfInterest& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object sensor_msgs::msg::RegionOfInterest that will be copied. + */ + eProsima_user_DllExport RegionOfInterest& operator=(RegionOfInterest&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x sensor_msgs::msg::RegionOfInterest object to compare. + */ + eProsima_user_DllExport bool operator==(const RegionOfInterest& x) const; + + /*! + * @brief Comparison operator. + * @param x sensor_msgs::msg::RegionOfInterest object to compare. + */ + eProsima_user_DllExport bool operator!=(const RegionOfInterest& x) const; + + /*! + * @brief This function sets a value in member x_offset + * @param _x_offset New value for member x_offset + */ + eProsima_user_DllExport void x_offset(uint32_t _x_offset); + + /*! + * @brief This function returns the value of member x_offset + * @return Value of member x_offset + */ + eProsima_user_DllExport uint32_t x_offset() const; + + /*! + * @brief This function returns a reference to member x_offset + * @return Reference to member x_offset + */ + eProsima_user_DllExport uint32_t& x_offset(); + + /*! + * @brief This function sets a value in member y_offset + * @param _y_offset New value for member y_offset + */ + eProsima_user_DllExport void y_offset(uint32_t _y_offset); + + /*! + * @brief This function returns the value of member y_offset + * @return Value of member y_offset + */ + eProsima_user_DllExport uint32_t y_offset() const; + + /*! + * @brief This function returns a reference to member y_offset + * @return Reference to member y_offset + */ + eProsima_user_DllExport uint32_t& y_offset(); + + /*! + * @brief This function sets a value in member height + * @param _height New value for member height + */ + eProsima_user_DllExport void height(uint32_t _height); + + /*! + * @brief This function returns the value of member height + * @return Value of member height + */ + eProsima_user_DllExport uint32_t height() const; + + /*! + * @brief This function returns a reference to member height + * @return Reference to member height + */ + eProsima_user_DllExport uint32_t& height(); + + /*! + * @brief This function sets a value in member width + * @param _width New value for member width + */ + eProsima_user_DllExport void width(uint32_t _width); + + /*! + * @brief This function returns the value of member width + * @return Value of member width + */ + eProsima_user_DllExport uint32_t width() const; + + /*! + * @brief This function returns a reference to member width + * @return Reference to member width + */ + eProsima_user_DllExport uint32_t& width(); + + /*! + * @brief This function sets a value in member do_rectify + * @param _do_rectify New value for member do_rectify + */ + eProsima_user_DllExport void do_rectify(bool _do_rectify); + + /*! + * @brief This function returns the value of member do_rectify + * @return Value of member do_rectify + */ + eProsima_user_DllExport bool do_rectify() const; + + /*! + * @brief This function returns a reference to member do_rectify + * @return Reference to member do_rectify + */ + eProsima_user_DllExport bool& do_rectify(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const sensor_msgs::msg::RegionOfInterest& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + uint32_t m_x_offset; + uint32_t m_y_offset; + uint32_t m_height; + uint32_t m_width; + bool m_do_rectify; +}; +} // namespace msg +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTEREST_H_ diff --git a/LibCarla/source/carla/ros2/types/RegionOfInterestPubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterestPubSubTypes.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/RegionOfInterestPubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterestPubSubTypes.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterestPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterestPubSubTypes.h new file mode 100644 index 00000000000..51dffdf9b7f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterestPubSubTypes.h @@ -0,0 +1,122 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file RegionOfInterestPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTEREST_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTEREST_PUBSUBTYPES_H_ + +#include +#include + +#include "RegionOfInterest.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error \ + Generated RegionOfInterest is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace sensor_msgs { +namespace msg { + +#ifndef SWIG +namespace detail { + +template +struct RegionOfInterest_rob { + friend constexpr typename Tag::type get(Tag) { + return M; + } +}; + +struct RegionOfInterest_f { + typedef bool RegionOfInterest::*type; + friend constexpr type get(RegionOfInterest_f); +}; + +template struct RegionOfInterest_rob; + +template +inline size_t constexpr RegionOfInterest_offset_of() { + return ((::size_t) & reinterpret_cast((((T*)0)->*get(Tag())))); +} +} // namespace detail +#endif + +/*! + * @brief This class represents the TopicDataType of the type RegionOfInterest defined by the user in the IDL file. + * @ingroup RegionOfInterest + */ +class RegionOfInterestPubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef RegionOfInterest type; + + eProsima_user_DllExport RegionOfInterestPubSubType(); + + eProsima_user_DllExport virtual ~RegionOfInterestPubSubType() override; + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return true; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return is_plain_impl(); + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + new (memory) RegionOfInterest(); + return true; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; + +private: + static constexpr bool is_plain_impl() { + return 17ULL == (detail::RegionOfInterest_offset_of() + sizeof(bool)); + } +}; +} // namespace msg +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTEREST_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitive.cxx b/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitive.cxx new file mode 100644 index 00000000000..a1e4f2dfeec --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitive.cxx @@ -0,0 +1,309 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SolidPrimitive.cpp + * This source file contains the definition of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "SolidPrimitive.h" +#include + +#include +using namespace eprosima::fastcdr::exception; + +#include + + + + + + + + + + + + + + + + +shape_msgs::msg::SolidPrimitive::SolidPrimitive() +{ + // m_type com.eprosima.idl.parser.typecode.PrimitiveTypeCode@43b9fd5 + m_type = 0; + // m_dimensions com.eprosima.idl.parser.typecode.SequenceTypeCode@79dc5318 + + // m_polygon com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@8e50104 + + +} + +shape_msgs::msg::SolidPrimitive::~SolidPrimitive() +{ + + +} + +shape_msgs::msg::SolidPrimitive::SolidPrimitive( + const SolidPrimitive& x) +{ + m_type = x.m_type; + m_dimensions = x.m_dimensions; + m_polygon = x.m_polygon; +} + +shape_msgs::msg::SolidPrimitive::SolidPrimitive( + SolidPrimitive&& x) +{ + m_type = x.m_type; + m_dimensions = std::move(x.m_dimensions); + m_polygon = std::move(x.m_polygon); +} + +shape_msgs::msg::SolidPrimitive& shape_msgs::msg::SolidPrimitive::operator =( + const SolidPrimitive& x) +{ + + m_type = x.m_type; + m_dimensions = x.m_dimensions; + m_polygon = x.m_polygon; + + return *this; +} + +shape_msgs::msg::SolidPrimitive& shape_msgs::msg::SolidPrimitive::operator =( + SolidPrimitive&& x) +{ + + m_type = x.m_type; + m_dimensions = std::move(x.m_dimensions); + m_polygon = std::move(x.m_polygon); + + return *this; +} + +bool shape_msgs::msg::SolidPrimitive::operator ==( + const SolidPrimitive& x) const +{ + + return (m_type == x.m_type && m_dimensions == x.m_dimensions && m_polygon == x.m_polygon); +} + +bool shape_msgs::msg::SolidPrimitive::operator !=( + const SolidPrimitive& x) const +{ + return !(*this == x); +} + +size_t shape_msgs::msg::SolidPrimitive::getMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + current_alignment += (3 * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + + + + current_alignment += geometry_msgs::msg::Polygon::getMaxCdrSerializedSize(current_alignment); + + return current_alignment - initial_alignment; +} + +size_t shape_msgs::msg::SolidPrimitive::getCdrSerializedSize( + const shape_msgs::msg::SolidPrimitive& data, + size_t current_alignment) +{ + (void)data; + size_t initial_alignment = current_alignment; + + + current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); + + + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); + + if (data.dimensions().size() > 0) + { + current_alignment += (data.dimensions().size() * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); + } + + + + current_alignment += geometry_msgs::msg::Polygon::getCdrSerializedSize(data.polygon(), current_alignment); + + return current_alignment - initial_alignment; +} + +void shape_msgs::msg::SolidPrimitive::serialize( + eprosima::fastcdr::Cdr& scdr) const +{ + + scdr << m_type; + scdr << m_dimensions; + scdr << m_polygon; + +} + +void shape_msgs::msg::SolidPrimitive::deserialize( + eprosima::fastcdr::Cdr& dcdr) +{ + + dcdr >> m_type; + dcdr >> m_dimensions; + dcdr >> m_polygon; +} + +/*! + * @brief This function sets a value in member type + * @param _type New value for member type + */ +void shape_msgs::msg::SolidPrimitive::type( + uint8_t _type) +{ + m_type = _type; +} + +/*! + * @brief This function returns the value of member type + * @return Value of member type + */ +uint8_t shape_msgs::msg::SolidPrimitive::type() const +{ + return m_type; +} + +/*! + * @brief This function returns a reference to member type + * @return Reference to member type + */ +uint8_t& shape_msgs::msg::SolidPrimitive::type() +{ + return m_type; +} + +/*! + * @brief This function copies the value in member dimensions + * @param _dimensions New value to be copied in member dimensions + */ +void shape_msgs::msg::SolidPrimitive::dimensions( + const std::vector& _dimensions) +{ + m_dimensions = _dimensions; +} + +/*! + * @brief This function moves the value in member dimensions + * @param _dimensions New value to be moved in member dimensions + */ +void shape_msgs::msg::SolidPrimitive::dimensions( + std::vector&& _dimensions) +{ + m_dimensions = std::move(_dimensions); +} + +/*! + * @brief This function returns a constant reference to member dimensions + * @return Constant reference to member dimensions + */ +const std::vector& shape_msgs::msg::SolidPrimitive::dimensions() const +{ + return m_dimensions; +} + +/*! + * @brief This function returns a reference to member dimensions + * @return Reference to member dimensions + */ +std::vector& shape_msgs::msg::SolidPrimitive::dimensions() +{ + return m_dimensions; +} +/*! + * @brief This function copies the value in member polygon + * @param _polygon New value to be copied in member polygon + */ +void shape_msgs::msg::SolidPrimitive::polygon( + const geometry_msgs::msg::Polygon& _polygon) +{ + m_polygon = _polygon; +} + +/*! + * @brief This function moves the value in member polygon + * @param _polygon New value to be moved in member polygon + */ +void shape_msgs::msg::SolidPrimitive::polygon( + geometry_msgs::msg::Polygon&& _polygon) +{ + m_polygon = std::move(_polygon); +} + +/*! + * @brief This function returns a constant reference to member polygon + * @return Constant reference to member polygon + */ +const geometry_msgs::msg::Polygon& shape_msgs::msg::SolidPrimitive::polygon() const +{ + return m_polygon; +} + +/*! + * @brief This function returns a reference to member polygon + * @return Reference to member polygon + */ +geometry_msgs::msg::Polygon& shape_msgs::msg::SolidPrimitive::polygon() +{ + return m_polygon; +} + +size_t shape_msgs::msg::SolidPrimitive::getKeyMaxCdrSerializedSize( + size_t current_alignment) +{ + size_t current_align = current_alignment; + + + + return current_align; +} + +bool shape_msgs::msg::SolidPrimitive::isKeyDefined() +{ + return false; +} + +void shape_msgs::msg::SolidPrimitive::serializeKey( + eprosima::fastcdr::Cdr& scdr) const +{ + (void) scdr; + +} + + diff --git a/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitive.h b/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitive.h new file mode 100644 index 00000000000..69d227167d0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitive.h @@ -0,0 +1,255 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SolidPrimitive.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_SHAPE_MSGS_MSG_SOLIDPRIMITIVE_H_ +#define _FAST_DDS_GENERATED_SHAPE_MSGS_MSG_SOLIDPRIMITIVE_H_ + +#include "geometry_msgs/msg/Polygon.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(SolidPrimitive_SOURCE) +#define SolidPrimitive_DllAPI __declspec(dllexport) +#else +#define SolidPrimitive_DllAPI __declspec(dllimport) +#endif // SolidPrimitive_SOURCE +#else +#define SolidPrimitive_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define SolidPrimitive_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace shape_msgs { +namespace msg { +namespace SolidPrimitive_Constants { +const uint8_t BOX = 1; +const uint8_t SPHERE = 2; +const uint8_t CYLINDER = 3; +const uint8_t CONE = 4; +const uint8_t PRISM = 5; +const uint8_t BOX_X = 0; +const uint8_t BOX_Y = 1; +const uint8_t BOX_Z = 2; +const uint8_t SPHERE_RADIUS = 0; +const uint8_t CYLINDER_HEIGHT = 0; +const uint8_t CYLINDER_RADIUS = 1; +const uint8_t CONE_HEIGHT = 0; +const uint8_t CONE_RADIUS = 1; +const uint8_t PRISM_HEIGHT = 0; +} // namespace SolidPrimitive_Constants +/*! + * @brief This class represents the structure SolidPrimitive defined by the user in the IDL file. + * @ingroup SOLIDPRIMITIVE + */ +class SolidPrimitive { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport SolidPrimitive(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~SolidPrimitive(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object shape_msgs::msg::SolidPrimitive that will be copied. + */ + eProsima_user_DllExport SolidPrimitive(const SolidPrimitive& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object shape_msgs::msg::SolidPrimitive that will be copied. + */ + eProsima_user_DllExport SolidPrimitive(SolidPrimitive&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object shape_msgs::msg::SolidPrimitive that will be copied. + */ + eProsima_user_DllExport SolidPrimitive& operator=(const SolidPrimitive& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object shape_msgs::msg::SolidPrimitive that will be copied. + */ + eProsima_user_DllExport SolidPrimitive& operator=(SolidPrimitive&& x); + + /*! + * @brief Comparison operator. + * @param x shape_msgs::msg::SolidPrimitive object to compare. + */ + eProsima_user_DllExport bool operator==(const SolidPrimitive& x) const; + + /*! + * @brief Comparison operator. + * @param x shape_msgs::msg::SolidPrimitive object to compare. + */ + eProsima_user_DllExport bool operator!=(const SolidPrimitive& x) const; + + /*! + * @brief This function sets a value in member type + * @param _type New value for member type + */ + eProsima_user_DllExport void type(uint8_t _type); + + /*! + * @brief This function returns the value of member type + * @return Value of member type + */ + eProsima_user_DllExport uint8_t type() const; + + /*! + * @brief This function returns a reference to member type + * @return Reference to member type + */ + eProsima_user_DllExport uint8_t& type(); + + /*! + * @brief This function copies the value in member dimensions + * @param _dimensions New value to be copied in member dimensions + */ + eProsima_user_DllExport void dimensions(const std::vector& _dimensions); + + /*! + * @brief This function moves the value in member dimensions + * @param _dimensions New value to be moved in member dimensions + */ + eProsima_user_DllExport void dimensions(std::vector&& _dimensions); + + /*! + * @brief This function returns a constant reference to member dimensions + * @return Constant reference to member dimensions + */ + eProsima_user_DllExport const std::vector& dimensions() const; + + /*! + * @brief This function returns a reference to member dimensions + * @return Reference to member dimensions + */ + eProsima_user_DllExport std::vector& dimensions(); + /*! + * @brief This function copies the value in member polygon + * @param _polygon New value to be copied in member polygon + */ + eProsima_user_DllExport void polygon(const geometry_msgs::msg::Polygon& _polygon); + + /*! + * @brief This function moves the value in member polygon + * @param _polygon New value to be moved in member polygon + */ + eProsima_user_DllExport void polygon(geometry_msgs::msg::Polygon&& _polygon); + + /*! + * @brief This function returns a constant reference to member polygon + * @return Constant reference to member polygon + */ + eProsima_user_DllExport const geometry_msgs::msg::Polygon& polygon() const; + + /*! + * @brief This function returns a reference to member polygon + * @return Reference to member polygon + */ + eProsima_user_DllExport geometry_msgs::msg::Polygon& polygon(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const shape_msgs::msg::SolidPrimitive& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + uint8_t m_type; + std::vector m_dimensions; + geometry_msgs::msg::Polygon m_polygon; +}; +} // namespace msg +} // namespace shape_msgs + +#endif // _FAST_DDS_GENERATED_SHAPE_MSGS_MSG_SOLIDPRIMITIVE_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitivePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitivePubSubTypes.cxx new file mode 100644 index 00000000000..d2903a0ff85 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitivePubSubTypes.cxx @@ -0,0 +1,193 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SolidPrimitivePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#include +#include + +#include "SolidPrimitivePubSubTypes.h" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; + +namespace shape_msgs { + namespace msg { + namespace SolidPrimitive_Constants { + + + + + + + + + + + + + + + + } //End of namespace SolidPrimitive_Constants + SolidPrimitivePubSubType::SolidPrimitivePubSubType() + { + setName("shape_msgs::msg::dds_::SolidPrimitive_"); + auto type_size = SolidPrimitive::getMaxCdrSerializedSize(); + type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ + m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ + m_isGetKeyDefined = SolidPrimitive::isKeyDefined(); + size_t keyLength = SolidPrimitive::getKeyMaxCdrSerializedSize() > 16 ? + SolidPrimitive::getKeyMaxCdrSerializedSize() : 16; + m_keyBuffer = reinterpret_cast(malloc(keyLength)); + memset(m_keyBuffer, 0, keyLength); + } + + SolidPrimitivePubSubType::~SolidPrimitivePubSubType() + { + if (m_keyBuffer != nullptr) + { + free(m_keyBuffer); + } + } + + bool SolidPrimitivePubSubType::serialize( + void* data, + SerializedPayload_t* payload) + { + SolidPrimitive* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + // Serialize encapsulation + ser.serialize_encapsulation(); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + // Get the serialized length + payload->length = static_cast(ser.getSerializedDataLength()); + return true; + } + + bool SolidPrimitivePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) + { + //Convert DATA to pointer of your type + SolidPrimitive* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + + // Object that deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, eprosima::fastcdr::Cdr::DDS_CDR); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + + return true; + } + + std::function SolidPrimitivePubSubType::getSerializedSizeProvider( + void* data) + { + return [data]() -> uint32_t + { + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; + }; + } + + void* SolidPrimitivePubSubType::createData() + { + return reinterpret_cast(new SolidPrimitive()); + } + + void SolidPrimitivePubSubType::deleteData( + void* data) + { + delete(reinterpret_cast(data)); + } + + bool SolidPrimitivePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) + { + if (!m_isGetKeyDefined) + { + return false; + } + + SolidPrimitive* p_type = static_cast(data); + + // Object that manages the raw buffer. + eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + SolidPrimitive::getKeyMaxCdrSerializedSize()); + + // Object that serializes the data. + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + p_type->serializeKey(ser); + if (force_md5 || SolidPrimitive::getKeyMaxCdrSerializedSize() > 16) + { + m_md5.init(); + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); + m_md5.finalize(); + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_md5.digest[i]; + } + } + else + { + for (uint8_t i = 0; i < 16; ++i) + { + handle->value[i] = m_keyBuffer[i]; + } + } + return true; + } + + + } //End of namespace msg + +} //End of namespace shape_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitivePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitivePubSubTypes.h new file mode 100644 index 00000000000..3db282002a6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitivePubSubTypes.h @@ -0,0 +1,92 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file SolidPrimitivePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_SHAPE_MSGS_MSG_SOLIDPRIMITIVE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_SHAPE_MSGS_MSG_SOLIDPRIMITIVE_PUBSUBTYPES_H_ + +#include +#include + +#include "SolidPrimitive.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated SolidPrimitive is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace shape_msgs { +namespace msg { +namespace SolidPrimitive_Constants {} +/*! + * @brief This class represents the TopicDataType of the type SolidPrimitive defined by the user in the IDL file. + * @ingroup SOLIDPRIMITIVE + */ +class SolidPrimitivePubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef SolidPrimitive type; + + eProsima_user_DllExport SolidPrimitivePubSubType(); + + eProsima_user_DllExport virtual ~SolidPrimitivePubSubType(); + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + (void)memory; + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; +}; +} // namespace msg +} // namespace shape_msgs + +#endif // _FAST_DDS_GENERATED_SHAPE_MSGS_MSG_SOLIDPRIMITIVE_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/Float32.cpp b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/Float32.cpp rename to LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32.h b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32.h new file mode 100644 index 00000000000..6ce054fac44 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32.h @@ -0,0 +1,190 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Float32.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32_H_ +#define _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32_H_ + +#include + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(Float32_SOURCE) +#define Float32_DllAPI __declspec(dllexport) +#else +#define Float32_DllAPI __declspec(dllimport) +#endif // Float32_SOURCE +#else +#define Float32_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define Float32_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace std_msgs { +namespace msg { +/*! + * @brief This class represents the structure Float32 defined by the user in the IDL file. + * @ingroup FLOAT32 + */ +class Float32 { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Float32(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Float32(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object std_msgs::msg::Float32 that will be copied. + */ + eProsima_user_DllExport Float32(const Float32& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object std_msgs::msg::Float32 that will be copied. + */ + eProsima_user_DllExport Float32(Float32&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object std_msgs::msg::Float32 that will be copied. + */ + eProsima_user_DllExport Float32& operator=(const Float32& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object std_msgs::msg::Float32 that will be copied. + */ + eProsima_user_DllExport Float32& operator=(Float32&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x std_msgs::msg::Float32 object to compare. + */ + eProsima_user_DllExport bool operator==(const Float32& x) const; + + /*! + * @brief Comparison operator. + * @param x std_msgs::msg::Float32 object to compare. + */ + eProsima_user_DllExport bool operator!=(const Float32& x) const; + + /*! + * @brief This function sets a value in member data + * @param _data New value for member data + */ + eProsima_user_DllExport void data(float _data); + + /*! + * @brief This function returns the value of member data + * @return Value of member data + */ + eProsima_user_DllExport float data() const; + + /*! + * @brief This function returns a reference to member data + * @return Reference to member data + */ + eProsima_user_DllExport float& data(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const std_msgs::msg::Float32& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + float m_data; +}; +} // namespace msg +} // namespace std_msgs + +#endif // _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32_H_ diff --git a/LibCarla/source/carla/ros2/types/Float32PubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32PubSubTypes.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/Float32PubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32PubSubTypes.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32PubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32PubSubTypes.h new file mode 100644 index 00000000000..f99d6d14933 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32PubSubTypes.h @@ -0,0 +1,118 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Float32PubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32_PUBSUBTYPES_H_ + +#include +#include + +#include "Float32.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated Float32 is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace std_msgs { +namespace msg { +#ifndef SWIG +namespace detail { +template +struct Float32_rob { + friend constexpr typename Tag::type get(Tag) { + return M; + } +}; + +struct Float32_f { + typedef float Float32::*type; + friend constexpr type get(Float32_f); +}; + +template struct Float32_rob; + +template +inline size_t constexpr Float32_offset_of() { + return ((::size_t) & reinterpret_cast((((T*)0)->*get(Tag())))); +} +} // namespace detail +#endif + +/*! + * @brief This class represents the TopicDataType of the type Float32 defined by the user in the IDL file. + * @ingroup FLOAT32 + */ +class Float32PubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef Float32 type; + + eProsima_user_DllExport Float32PubSubType(); + + eProsima_user_DllExport virtual ~Float32PubSubType() override; + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return true; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return is_plain_impl(); + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + new (memory) Float32(); + return true; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; + unsigned char* m_keyBuffer; + +private: + static constexpr bool is_plain_impl() { + return 4ULL == (detail::Float32_offset_of() + sizeof(float)); + } +}; +} // namespace msg +} // namespace std_msgs + +#endif // _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/Header.cpp b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Header.cxx similarity index 87% rename from LibCarla/source/carla/ros2/types/Header.cpp rename to LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Header.cxx index 04d098fe866..9311644b3f5 100644 --- a/LibCarla/source/carla/ros2/types/Header.cpp +++ b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Header.cxx @@ -26,7 +26,7 @@ char dummy; } // namespace #endif // _WIN32 -#include "Header.h" +#include "std_msgs/msg/Header.h" #include #include @@ -34,18 +34,18 @@ using namespace eprosima::fastcdr::exception; #include -#define builtin_interfaces_msg_Time_max_cdr_typesize 8ULL; -#define std_msgs_msg_Header_max_cdr_typesize 268ULL; -#define builtin_interfaces_msg_Time_max_key_cdr_typesize 0ULL; -#define std_msgs_msg_Header_max_key_cdr_typesize 0ULL; - std_msgs::msg::Header::Header() { + // m_stamp com.eprosima.fastdds.idl.parser.typecode.StructTypeCode@58e1d9d + + // m_frame_id com.eprosima.idl.parser.typecode.StringTypeCode@446a1e84 m_frame_id =""; + } std_msgs::msg::Header::~Header() { + } std_msgs::msg::Header::Header( @@ -56,7 +56,7 @@ std_msgs::msg::Header::Header( } std_msgs::msg::Header::Header( - Header&& x) noexcept + Header&& x) { m_stamp = std::move(x.m_stamp); m_frame_id = std::move(x.m_frame_id); @@ -65,6 +65,7 @@ std_msgs::msg::Header::Header( std_msgs::msg::Header& std_msgs::msg::Header::operator =( const Header& x) { + m_stamp = x.m_stamp; m_frame_id = x.m_frame_id; @@ -72,8 +73,9 @@ std_msgs::msg::Header& std_msgs::msg::Header::operator =( } std_msgs::msg::Header& std_msgs::msg::Header::operator =( - Header&& x) noexcept + Header&& x) { + m_stamp = std::move(x.m_stamp); m_frame_id = std::move(x.m_frame_id); @@ -83,6 +85,7 @@ std_msgs::msg::Header& std_msgs::msg::Header::operator =( bool std_msgs::msg::Header::operator ==( const Header& x) const { + return (m_stamp == x.m_stamp && m_frame_id == x.m_frame_id); } @@ -95,31 +98,44 @@ bool std_msgs::msg::Header::operator !=( size_t std_msgs::msg::Header::getMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return std_msgs_msg_Header_max_cdr_typesize; + size_t initial_alignment = current_alignment; + + + current_alignment += builtin_interfaces::msg::Time::getMaxCdrSerializedSize(current_alignment); + current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1; + + + return current_alignment - initial_alignment; } size_t std_msgs::msg::Header::getCdrSerializedSize( const std_msgs::msg::Header& data, size_t current_alignment) { + (void)data; size_t initial_alignment = current_alignment; + + current_alignment += builtin_interfaces::msg::Time::getCdrSerializedSize(data.stamp(), current_alignment); current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.frame_id().size() + 1; + return current_alignment - initial_alignment; } void std_msgs::msg::Header::serialize( eprosima::fastcdr::Cdr& scdr) const { + scdr << m_stamp; - scdr << m_frame_id.c_str(); + scdr << m_frame_id; + } void std_msgs::msg::Header::deserialize( eprosima::fastcdr::Cdr& dcdr) { + dcdr >> m_stamp; dcdr >> m_frame_id; } @@ -199,12 +215,14 @@ std::string& std_msgs::msg::Header::frame_id() return m_frame_id; } - size_t std_msgs::msg::Header::getKeyMaxCdrSerializedSize( size_t current_alignment) { - static_cast(current_alignment); - return std_msgs_msg_Header_max_key_cdr_typesize; + size_t current_align = current_alignment; + + + + return current_align; } bool std_msgs::msg::Header::isKeyDefined() @@ -216,4 +234,7 @@ void std_msgs::msg::Header::serializeKey( eprosima::fastcdr::Cdr& scdr) const { (void) scdr; + } + + diff --git a/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Header.h b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Header.h new file mode 100644 index 00000000000..15c0b45c5af --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Header.h @@ -0,0 +1,220 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file Header.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADER_H_ +#define _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADER_H_ + +#include "builtin_interfaces/msg/Time.h" + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(Header_SOURCE) +#define Header_DllAPI __declspec(dllexport) +#else +#define Header_DllAPI __declspec(dllimport) +#endif // Header_SOURCE +#else +#define Header_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define Header_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace std_msgs { +namespace msg { +/*! + * @brief This class represents the structure Header defined by the user in the IDL file. + * @ingroup HEADER + */ +class Header { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Header(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Header(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object std_msgs::msg::Header that will be copied. + */ + eProsima_user_DllExport Header(const Header& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object std_msgs::msg::Header that will be copied. + */ + eProsima_user_DllExport Header(Header&& x); + + /*! + * @brief Copy assignment. + * @param x Reference to the object std_msgs::msg::Header that will be copied. + */ + eProsima_user_DllExport Header& operator=(const Header& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object std_msgs::msg::Header that will be copied. + */ + eProsima_user_DllExport Header& operator=(Header&& x); + + /*! + * @brief Comparison operator. + * @param x std_msgs::msg::Header object to compare. + */ + eProsima_user_DllExport bool operator==(const Header& x) const; + + /*! + * @brief Comparison operator. + * @param x std_msgs::msg::Header object to compare. + */ + eProsima_user_DllExport bool operator!=(const Header& x) const; + + /*! + * @brief This function copies the value in member stamp + * @param _stamp New value to be copied in member stamp + */ + eProsima_user_DllExport void stamp(const builtin_interfaces::msg::Time& _stamp); + + /*! + * @brief This function moves the value in member stamp + * @param _stamp New value to be moved in member stamp + */ + eProsima_user_DllExport void stamp(builtin_interfaces::msg::Time&& _stamp); + + /*! + * @brief This function returns a constant reference to member stamp + * @return Constant reference to member stamp + */ + eProsima_user_DllExport const builtin_interfaces::msg::Time& stamp() const; + + /*! + * @brief This function returns a reference to member stamp + * @return Reference to member stamp + */ + eProsima_user_DllExport builtin_interfaces::msg::Time& stamp(); + /*! + * @brief This function copies the value in member frame_id + * @param _frame_id New value to be copied in member frame_id + */ + eProsima_user_DllExport void frame_id(const std::string& _frame_id); + + /*! + * @brief This function moves the value in member frame_id + * @param _frame_id New value to be moved in member frame_id + */ + eProsima_user_DllExport void frame_id(std::string&& _frame_id); + + /*! + * @brief This function returns a constant reference to member frame_id + * @return Constant reference to member frame_id + */ + eProsima_user_DllExport const std::string& frame_id() const; + + /*! + * @brief This function returns a reference to member frame_id + * @return Reference to member frame_id + */ + eProsima_user_DllExport std::string& frame_id(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const std_msgs::msg::Header& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + builtin_interfaces::msg::Time m_stamp; + std::string m_frame_id; +}; +} // namespace msg +} // namespace std_msgs + +#endif // _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADER_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/HeaderPubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/HeaderPubSubTypes.cxx similarity index 90% rename from LibCarla/source/carla/ros2/types/HeaderPubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/std_msgs/msg/HeaderPubSubTypes.cxx index e61f4ee873c..119a111258f 100644 --- a/LibCarla/source/carla/ros2/types/HeaderPubSubTypes.cpp +++ b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/HeaderPubSubTypes.cxx @@ -19,10 +19,11 @@ * This file was generated by the tool fastcdrgen. */ + #include #include -#include "HeaderPubSubTypes.h" +#include "std_msgs/msg/HeaderPubSubTypes.h" using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; @@ -63,7 +64,17 @@ namespace std_msgs { payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; // Serialize encapsulation ser.serialize_encapsulation(); - p_type->serialize(ser); + + try + { + // Serialize the object. + p_type->serialize(ser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + // Get the serialized length payload->length = static_cast(ser.getSerializedDataLength()); return true; @@ -86,8 +97,16 @@ namespace std_msgs { deser.read_encapsulation(); payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - // Deserialize the object. - p_type->deserialize(deser); + try + { + // Deserialize the object. + p_type->deserialize(deser); + } + catch (eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/) + { + return false; + } + return true; } @@ -150,5 +169,8 @@ namespace std_msgs { } return true; } + + } //End of namespace msg + } //End of namespace std_msgs diff --git a/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/HeaderPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/HeaderPubSubTypes.h new file mode 100644 index 00000000000..5a1aeecb15b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/HeaderPubSubTypes.h @@ -0,0 +1,91 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file HeaderPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADER_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADER_PUBSUBTYPES_H_ + +#include +#include + +#include "std_msgs/msg/Header.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated Header is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace std_msgs { +namespace msg { +/*! + * @brief This class represents the TopicDataType of the type Header defined by the user in the IDL file. + * @ingroup HEADER + */ +class HeaderPubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef Header type; + + eProsima_user_DllExport HeaderPubSubType(); + + eProsima_user_DllExport virtual ~HeaderPubSubType(); + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + (void)memory; + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + + MD5 m_md5; + unsigned char* m_keyBuffer; +}; +} // namespace msg +} // namespace std_msgs + +#endif // _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADER_PUBSUBTYPES_H_ \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/String.cpp b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/String.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/String.cpp rename to LibCarla/source/carla/ros2/fastdds/std_msgs/msg/String.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/String.h b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/String.h new file mode 100644 index 00000000000..b50251f6a8e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/String.h @@ -0,0 +1,196 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file String.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_STD_MSGS_MSG_STRING_H_ +#define _FAST_DDS_GENERATED_STD_MSGS_MSG_STRING_H_ + +#include + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(String_SOURCE) +#define String_DllAPI __declspec(dllexport) +#else +#define String_DllAPI __declspec(dllimport) +#endif // String_SOURCE +#else +#define String_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define String_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace std_msgs { +namespace msg { +/*! + * @brief This class represents the structure String defined by the user in the IDL file. + * @ingroup STRING + */ +class String { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport String(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~String(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object std_msgs::msg::String that will be copied. + */ + eProsima_user_DllExport String(const String& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object std_msgs::msg::String that will be copied. + */ + eProsima_user_DllExport String(String&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object std_msgs::msg::String that will be copied. + */ + eProsima_user_DllExport String& operator=(const String& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object std_msgs::msg::String that will be copied. + */ + eProsima_user_DllExport String& operator=(String&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x std_msgs::msg::String object to compare. + */ + eProsima_user_DllExport bool operator==(const String& x) const; + + /*! + * @brief Comparison operator. + * @param x std_msgs::msg::String object to compare. + */ + eProsima_user_DllExport bool operator!=(const String& x) const; + + /*! + * @brief This function copies the value in member data + * @param _data New value to be copied in member data + */ + eProsima_user_DllExport void data(const std::string& _data); + + /*! + * @brief This function moves the value in member data + * @param _data New value to be moved in member data + */ + eProsima_user_DllExport void data(std::string&& _data); + + /*! + * @brief This function returns a constant reference to member data + * @return Constant reference to member data + */ + eProsima_user_DllExport const std::string& data() const; + + /*! + * @brief This function returns a reference to member data + * @return Reference to member data + */ + eProsima_user_DllExport std::string& data(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const std_msgs::msg::String& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + std::string m_data; +}; +} // namespace msg +} // namespace std_msgs + +#endif // _FAST_DDS_GENERATED_STD_MSGS_MSG_STRING_H_ diff --git a/LibCarla/source/carla/ros2/types/StringPubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/StringPubSubTypes.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/StringPubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/std_msgs/msg/StringPubSubTypes.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/StringPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/StringPubSubTypes.h new file mode 100644 index 00000000000..40561ef040f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/StringPubSubTypes.h @@ -0,0 +1,91 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file StringPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_STD_MSGS_MSG_STRING_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_STD_MSGS_MSG_STRING_PUBSUBTYPES_H_ + +#include +#include + +#include "String.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated String is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace std_msgs { +namespace msg { + +/*! + * @brief This class represents the TopicDataType of the type String defined by the user in the IDL file. + * @ingroup STRING + */ +class StringPubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef String type; + + eProsima_user_DllExport StringPubSubType(); + + eProsima_user_DllExport virtual ~StringPubSubType() override; + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + (void)memory; + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; + unsigned char* m_keyBuffer; +}; +} // namespace msg +} // namespace std_msgs + +#endif // _FAST_DDS_GENERATED_STD_MSGS_MSG_STRING_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/TF2Error.cpp b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TF2Error.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/TF2Error.cpp rename to LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TF2Error.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TF2Error.h b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TF2Error.h new file mode 100644 index 00000000000..ca688329403 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TF2Error.h @@ -0,0 +1,222 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file TF2Error.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_TF2_MSGS_MSG_TF2ERROR_H_ +#define _FAST_DDS_GENERATED_TF2_MSGS_MSG_TF2ERROR_H_ + +#include + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(TF2Error_SOURCE) +#define TF2Error_DllAPI __declspec(dllexport) +#else +#define TF2Error_DllAPI __declspec(dllimport) +#endif // TF2Error_SOURCE +#else +#define TF2Error_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define TF2Error_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace tf2_msgs { +namespace msg { +const uint8_t TF2Error__NO_ERROR = 0; +const uint8_t TF2Error__LOOKUP_ERROR = 1; +const uint8_t TF2Error__CONNECTIVITY_ERROR = 2; +const uint8_t TF2Error__EXTRAPOLATION_ERROR = 3; +const uint8_t TF2Error__INVALID_ARGUMENT_ERROR = 4; +const uint8_t TF2Error__TIMEOUT_ERROR = 5; +const uint8_t TF2Error__TRANSFORM_ERROR = 6; +/*! + * @brief This class represents the structure TF2Error defined by the user in the IDL file. + * @ingroup TF2ERROR + */ +class TF2Error { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport TF2Error(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~TF2Error(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object tf2_msgs::msg::TF2Error that will be copied. + */ + eProsima_user_DllExport TF2Error(const TF2Error& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object tf2_msgs::msg::TF2Error that will be copied. + */ + eProsima_user_DllExport TF2Error(TF2Error&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object tf2_msgs::msg::TF2Error that will be copied. + */ + eProsima_user_DllExport TF2Error& operator=(const TF2Error& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object tf2_msgs::msg::TF2Error that will be copied. + */ + eProsima_user_DllExport TF2Error& operator=(TF2Error&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x tf2_msgs::msg::TF2Error object to compare. + */ + eProsima_user_DllExport bool operator==(const TF2Error& x) const; + + /*! + * @brief Comparison operator. + * @param x tf2_msgs::msg::TF2Error object to compare. + */ + eProsima_user_DllExport bool operator!=(const TF2Error& x) const; + + /*! + * @brief This function sets a value in member error + * @param _error New value for member error + */ + eProsima_user_DllExport void error(uint8_t _error); + + /*! + * @brief This function returns the value of member error + * @return Value of member error + */ + eProsima_user_DllExport uint8_t error() const; + + /*! + * @brief This function returns a reference to member error + * @return Reference to member error + */ + eProsima_user_DllExport uint8_t& error(); + + /*! + * @brief This function copies the value in member error_string + * @param _error_string New value to be copied in member error_string + */ + eProsima_user_DllExport void error_string(const std::string& _error_string); + + /*! + * @brief This function moves the value in member error_string + * @param _error_string New value to be moved in member error_string + */ + eProsima_user_DllExport void error_string(std::string&& _error_string); + + /*! + * @brief This function returns a constant reference to member error_string + * @return Constant reference to member error_string + */ + eProsima_user_DllExport const std::string& error_string() const; + + /*! + * @brief This function returns a reference to member error_string + * @return Reference to member error_string + */ + eProsima_user_DllExport std::string& error_string(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const tf2_msgs::msg::TF2Error& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + uint8_t m_error; + std::string m_error_string; +}; +} // namespace msg +} // namespace tf2_msgs + +#endif // _FAST_DDS_GENERATED_TF2_MSGS_MSG_TF2ERROR_H_ diff --git a/LibCarla/source/carla/ros2/types/TF2ErrorPubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TF2ErrorPubSubTypes.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/TF2ErrorPubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TF2ErrorPubSubTypes.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TF2ErrorPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TF2ErrorPubSubTypes.h new file mode 100644 index 00000000000..c63c7bd3fc9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TF2ErrorPubSubTypes.h @@ -0,0 +1,90 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file TF2ErrorPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_TF2_MSGS_MSG_TF2ERROR_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_TF2_MSGS_MSG_TF2ERROR_PUBSUBTYPES_H_ + +#include +#include + +#include "TF2Error.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated TF2Error is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace tf2_msgs { +namespace msg { +/*! + * @brief This class represents the TopicDataType of the type TF2Error defined by the user in the IDL file. + * @ingroup TF2ERROR + */ +class TF2ErrorPubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef TF2Error type; + + eProsima_user_DllExport TF2ErrorPubSubType(); + + eProsima_user_DllExport virtual ~TF2ErrorPubSubType() override; + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + (void)memory; + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; + unsigned char* m_keyBuffer; +}; +} // namespace msg +} // namespace tf2_msgs + +#endif // _FAST_DDS_GENERATED_TF2_MSGS_MSG_TF2ERROR_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/TFMessage.cpp b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessage.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/TFMessage.cpp rename to LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessage.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessage.h b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessage.h new file mode 100644 index 00000000000..f10efd2114e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessage.h @@ -0,0 +1,198 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file TFMessage.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool gen. + */ + +#ifndef _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGE_H_ +#define _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGE_H_ + +#include "geometry_msgs/msg/TransformStamped.h" + +#include + +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#define eProsima_user_DllExport __declspec(dllexport) +#else +#define eProsima_user_DllExport +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define eProsima_user_DllExport +#endif // _WIN32 + +#if defined(_WIN32) +#if defined(EPROSIMA_USER_DLL_EXPORT) +#if defined(TFMessage_SOURCE) +#define TFMessage_DllAPI __declspec(dllexport) +#else +#define TFMessage_DllAPI __declspec(dllimport) +#endif // TFMessage_SOURCE +#else +#define TFMessage_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define TFMessage_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +} // namespace fastcdr +} // namespace eprosima + +namespace tf2_msgs { +namespace msg { +/*! + * @brief This class represents the structure TFMessage defined by the user in the IDL file. + * @ingroup TFMESSAGE + */ +class TFMessage { +public: + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport TFMessage(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~TFMessage(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object tf2_msgs::msg::TFMessage that will be copied. + */ + eProsima_user_DllExport TFMessage(const TFMessage& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object tf2_msgs::msg::TFMessage that will be copied. + */ + eProsima_user_DllExport TFMessage(TFMessage&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object tf2_msgs::msg::TFMessage that will be copied. + */ + eProsima_user_DllExport TFMessage& operator=(const TFMessage& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object tf2_msgs::msg::TFMessage that will be copied. + */ + eProsima_user_DllExport TFMessage& operator=(TFMessage&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x tf2_msgs::msg::TFMessage object to compare. + */ + eProsima_user_DllExport bool operator==(const TFMessage& x) const; + + /*! + * @brief Comparison operator. + * @param x tf2_msgs::msg::TFMessage object to compare. + */ + eProsima_user_DllExport bool operator!=(const TFMessage& x) const; + + /*! + * @brief This function copies the value in member transforms + * @param _transforms New value to be copied in member transforms + */ + eProsima_user_DllExport void transforms(const std::vector& _transforms); + + /*! + * @brief This function moves the value in member transforms + * @param _transforms New value to be moved in member transforms + */ + eProsima_user_DllExport void transforms(std::vector&& _transforms); + + /*! + * @brief This function returns a constant reference to member transforms + * @return Constant reference to member transforms + */ + eProsima_user_DllExport const std::vector& transforms() const; + + /*! + * @brief This function returns a reference to member transforms + * @return Reference to member transforms + */ + eProsima_user_DllExport std::vector& transforms(); + + /*! + * @brief This function returns the maximum serialized size of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function returns the serialized size of a data depending on the buffer alignment. + * @param data Data which is calculated its serialized size. + * @param current_alignment Buffer alignment. + * @return Serialized size. + */ + eProsima_user_DllExport static size_t getCdrSerializedSize(const tf2_msgs::msg::TFMessage& data, + size_t current_alignment = 0); + + /*! + * @brief This function serializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr& cdr) const; + + /*! + * @brief This function deserializes an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr& cdr); + + /*! + * @brief This function returns the maximum serialized size of the Key of an object + * depending on the buffer alignment. + * @param current_alignment Buffer alignment. + * @return Maximum serialized size. + */ + eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0); + + /*! + * @brief This function tells you if the Key has been defined for this type + */ + eProsima_user_DllExport static bool isKeyDefined(); + + /*! + * @brief This function serializes the key members of an object using CDR serialization. + * @param cdr CDR serialization object. + */ + eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr& cdr) const; + +private: + std::vector m_transforms; +}; +} // namespace msg +} // namespace tf2_msgs + +#endif // _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGE_H_ diff --git a/LibCarla/source/carla/ros2/types/TFMessagePubSubTypes.cpp b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessagePubSubTypes.cxx similarity index 100% rename from LibCarla/source/carla/ros2/types/TFMessagePubSubTypes.cpp rename to LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessagePubSubTypes.cxx diff --git a/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessagePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessagePubSubTypes.h new file mode 100644 index 00000000000..8d1749ce5df --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessagePubSubTypes.h @@ -0,0 +1,93 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// 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. + +/*! + * @file TFMessagePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#ifndef _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGE_PUBSUBTYPES_H_ + +#include +#include + +#include "TFMessage.h" + +#include "geometry_msgs/msg/TransformStampedPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 1) +#error Generated TFMessage is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace tf2_msgs { +namespace msg { + +/*! + * @brief This class represents the TopicDataType of the type TFMessage defined by the user in the IDL file. + * @ingroup TFMESSAGE + */ +class TFMessagePubSubType : public eprosima::fastdds::dds::TopicDataType { +public: + typedef TFMessage type; + + eProsima_user_DllExport TFMessagePubSubType(); + + eProsima_user_DllExport virtual ~TFMessagePubSubType() override; + + eProsima_user_DllExport virtual bool serialize(void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; + + eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport virtual std::function getSerializedSizeProvider(void* data) override; + + eProsima_user_DllExport virtual bool getKey(void* data, eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport virtual void* createData() override; + + eProsima_user_DllExport virtual void deleteData(void* data) override; + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + eProsima_user_DllExport inline bool is_bounded() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED + +#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + eProsima_user_DllExport inline bool is_plain() const override { + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN + +#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + eProsima_user_DllExport inline bool construct_sample(void* memory) const override { + (void)memory; + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + MD5 m_md5; + unsigned char* m_keyBuffer; +}; +} // namespace msg +} // namespace tf2_msgs + +#endif // _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGE_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/publishers/BasePublisher.h b/LibCarla/source/carla/ros2/publishers/BasePublisher.h deleted file mode 100644 index 0e1462d61b5..00000000000 --- a/LibCarla/source/carla/ros2/publishers/BasePublisher.h +++ /dev/null @@ -1,44 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include - -namespace carla { -namespace ros2 { - - class BasePublisher { - public: - - BasePublisher() {} - - BasePublisher(std::string base_topic_name) : - _base_topic_name(base_topic_name) {} - - BasePublisher(std::string base_topic_name, std::string frame_id) : - _base_topic_name(base_topic_name), - _frame_id(frame_id) {} - - BasePublisher(void* actor, std::string base_topic_name, std::string frame_id) : - _actor(actor), - _base_topic_name(base_topic_name), - _frame_id(frame_id) {} - - const std::string GetBaseTopicName() {return _base_topic_name; } - const std::string GetFrameId() { return _frame_id; } - - virtual bool Publish() = 0; - - void* GetActor() { return _actor; } - - protected: - std::string _frame_id = ""; - std::string _base_topic_name = ""; - - void* _actor { nullptr }; - }; - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaActorListPublisher.cpp b/LibCarla/source/carla/ros2/publishers/CarlaActorListPublisher.cpp new file mode 100644 index 00000000000..b8b9b8e8595 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/CarlaActorListPublisher.cpp @@ -0,0 +1,35 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "CarlaActorListPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +CarlaActorListPublisher::CarlaActorListPublisher(std::string const &role_name) + : PublisherBase(carla::ros2::types::ActorNameDefinition::CreateFromRoleName(role_name)), + _impl(std::make_shared()) {} + +bool CarlaActorListPublisher::Init(std::shared_ptr domain_participant) { + auto topic_qos = get_topic_qos(); + topic_qos.transient_local(); + return _impl->Init(domain_participant, get_topic_name(), topic_qos); +} + +bool CarlaActorListPublisher::Publish() { + return _impl->Publish(); +} + +bool CarlaActorListPublisher::SubscribersConnected() const { + return _impl->SubscribersConnected(); +} + +void CarlaActorListPublisher::UpdateCarlaActorList(const carla_msgs::msg::CarlaActorList& status) { + _impl->Message() = status; + _impl->SetMessageUpdated(); +} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaActorListPublisher.h b/LibCarla/source/carla/ros2/publishers/CarlaActorListPublisher.h new file mode 100644 index 00000000000..2733145895a --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/CarlaActorListPublisher.h @@ -0,0 +1,41 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/PublisherBase.h" +#include "carla_msgs/msg/CarlaActorListPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using CarlaActorListPublisherImpl = + DdsPublisherImpl; + +class CarlaActorListPublisher : public PublisherBase { +public: + CarlaActorListPublisher(std::string const &role_name); + virtual ~CarlaActorListPublisher() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + void UpdateCarlaActorList(const carla_msgs::msg::CarlaActorList& actor_list); + +private: + std::shared_ptr _impl; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaCameraPublisher.cpp b/LibCarla/source/carla/ros2/publishers/CarlaCameraPublisher.cpp deleted file mode 100644 index d11bbe7471c..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaCameraPublisher.cpp +++ /dev/null @@ -1,63 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "CarlaCameraPublisher.h" - -namespace carla { -namespace ros2 { - -std::vector CarlaCameraPublisher::ComputeImage(uint32_t height, uint32_t width, const uint8_t *data) { - const size_t size = height * width * this->GetChannels() * sizeof(uint8_t); - std::vector vector_data(data, data + size); - return vector_data; -} - -bool CarlaCameraPublisher::WriteCameraInfo(int32_t seconds, uint32_t nanoseconds, uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify) { - - _impl_camera_info->GetMessage()->header().stamp().sec(seconds); - _impl_camera_info->GetMessage()->header().stamp().nanosec(nanoseconds); - _impl_camera_info->GetMessage()->header().frame_id(GetFrameId()); - - const double cx = static_cast(width) / 2.0; - const double cy = static_cast(height) / 2.0; - const double fx = static_cast(width) / (2.0 * std::tan(fov) * M_PI / 360.0); - const double fy = fx; - - _impl_camera_info->GetMessage()->height(height); - _impl_camera_info->GetMessage()->width(width); - _impl_camera_info->GetMessage()->distortion_model("plumb_bob"); - _impl_camera_info->GetMessage()->D({ 0.0, 0.0, 0.0, 0.0, 0.0 }); - _impl_camera_info->GetMessage()->k({fx, 0.0, cx, 0.0, fy, cy, 0.0, 0.0, 1.0}); - _impl_camera_info->GetMessage()->r({ 1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0 }); - _impl_camera_info->GetMessage()->p({fx, 0.0, cx, 0.0, 0.0, fy, cy, 0.0, 0.0, 0.0, 1.0, 0.0}); - _impl_camera_info->GetMessage()->binning_x(0); - _impl_camera_info->GetMessage()->binning_y(0); - - _impl_camera_info->GetMessage()->roi().x_offset(x_offset); - _impl_camera_info->GetMessage()->roi().y_offset(y_offset); - _impl_camera_info->GetMessage()->roi().height(height); - _impl_camera_info->GetMessage()->roi().width(width); - _impl_camera_info->GetMessage()->roi().do_rectify(do_rectify); - - return true; -} - -bool CarlaCameraPublisher::WriteImage(int32_t seconds, uint32_t nanoseconds, uint32_t height, uint32_t width, std::vector data) { - _impl_image->GetMessage()->header().stamp().sec(seconds); - _impl_image->GetMessage()->header().stamp().nanosec(nanoseconds); - _impl_image->GetMessage()->header().frame_id(this->GetFrameId()); - - _impl_image->GetMessage()->width(width); - _impl_image->GetMessage()->height(height); - _impl_image->GetMessage()->encoding(this->GetEncoding()); - _impl_image->GetMessage()->is_bigendian(0); - _impl_image->GetMessage()->step(width * this->GetChannels() * sizeof(uint8_t)); - - _impl_image->GetMessage()->data(std::move(data)); // https://github.com/eProsima/Fast-DDS/issues/2330 - - return true; -} - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaCameraPublisher.h b/LibCarla/source/carla/ros2/publishers/CarlaCameraPublisher.h deleted file mode 100644 index 523b152a5c7..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaCameraPublisher.h +++ /dev/null @@ -1,64 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include -#include - -#include "carla/ros2/publishers/BasePublisher.h" -#include "carla/ros2/publishers/PublisherImpl.h" - -#include "carla/ros2/types/Image.h" -#include "carla/ros2/types/ImagePubSubTypes.h" -#include "carla/ros2/types/CameraInfo.h" -#include "carla/ros2/types/CameraInfoPubSubTypes.h" - -namespace carla { -namespace ros2 { - - class CarlaCameraPublisher : public BasePublisher { - public: - struct ImageMsgTraits { - using msg_type = sensor_msgs::msg::Image; - using msg_pubsub_type = sensor_msgs::msg::ImagePubSubType; - }; - - struct CameraInfoMsgTraits { - using msg_type = sensor_msgs::msg::CameraInfo; - using msg_pubsub_type = sensor_msgs::msg::CameraInfoPubSubType; - }; - - CarlaCameraPublisher(std::string base_topic_name, std::string frame_id) : - BasePublisher(base_topic_name, frame_id), - _impl_image(std::make_shared>()), - _impl_camera_info(std::make_shared>()) { - _impl_image->Init(GetBaseTopicName() + "/image"); - _impl_camera_info->Init(GetBaseTopicName() + "/camera_info"); - } - - virtual uint8_t GetChannels() = 0; - - bool Publish() { - return _impl_camera_info->Publish() && _impl_image->Publish(); - } - - bool WriteCameraInfo(int32_t seconds, uint32_t nanoseconds, uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify); - bool WriteImage(int32_t seconds, uint32_t nanoseconds, uint32_t height, uint32_t width, const uint8_t* data) { - return WriteImage(seconds, nanoseconds, height, width, ComputeImage(height, width, data)); - } - bool WriteImage(int32_t seconds, uint32_t nanoseconds, uint32_t height, uint32_t width, std::vector data); - - private: - virtual std::string GetEncoding() = 0; - - virtual std::vector ComputeImage(uint32_t height, uint32_t width, const uint8_t* data); - - private: - std::shared_ptr> _impl_image; - std::shared_ptr> _impl_camera_info; - }; - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaClockPublisher.cpp b/LibCarla/source/carla/ros2/publishers/CarlaClockPublisher.cpp deleted file mode 100644 index 2f287c25776..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaClockPublisher.cpp +++ /dev/null @@ -1,18 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "CarlaClockPublisher.h" - -namespace carla { -namespace ros2 { - -bool CarlaClockPublisher::Write(int32_t seconds, uint32_t nanoseconds) { - _impl->GetMessage()->clock().sec(seconds); - _impl->GetMessage()->clock().nanosec(nanoseconds); - - return true; -} - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaClockPublisher.h b/LibCarla/source/carla/ros2/publishers/CarlaClockPublisher.h deleted file mode 100644 index 85dca7e225f..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaClockPublisher.h +++ /dev/null @@ -1,42 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include - -#include "carla/ros2/publishers/BasePublisher.h" -#include "carla/ros2/publishers/PublisherImpl.h" - -#include "carla/ros2/types/Clock.h" -#include "carla/ros2/types/ClockPubSubTypes.h" - -namespace carla { -namespace ros2 { - - class CarlaClockPublisher : public BasePublisher { - public: - struct ClockMsgTraits { - using msg_type = rosgraph::msg::Clock; - using msg_pubsub_type = rosgraph::msg::ClockPubSubType; - }; - - CarlaClockPublisher() : - BasePublisher("rt/clock"), - _impl(std::make_shared>()) { - _impl->Init(GetBaseTopicName()); - } - - bool Publish() { - return _impl->Publish(); - } - - bool Write(int32_t seconds, uint32_t nanoseconds); - - private: - std::shared_ptr> _impl; - }; - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaCollisionPublisher.cpp b/LibCarla/source/carla/ros2/publishers/CarlaCollisionPublisher.cpp deleted file mode 100644 index c5879c9d7ed..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaCollisionPublisher.cpp +++ /dev/null @@ -1,26 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "CarlaCollisionPublisher.h" - -namespace carla { -namespace ros2 { - -bool CarlaCollisionPublisher::Write(int32_t seconds, uint32_t nanoseconds, uint32_t actor_id, geom::Vector3D impulse) { - - _impl->GetMessage()->header().stamp().sec(seconds); - _impl->GetMessage()->header().stamp().nanosec(nanoseconds); - _impl->GetMessage()->header().frame_id(GetFrameId()); - - _impl->GetMessage()->other_actor_id(actor_id); - - _impl->GetMessage()->normal_impulse().x(impulse.x); - _impl->GetMessage()->normal_impulse().y(impulse.y); - _impl->GetMessage()->normal_impulse().z(impulse.z); - - return true; -} - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaCollisionPublisher.h b/LibCarla/source/carla/ros2/publishers/CarlaCollisionPublisher.h deleted file mode 100644 index 081eda3dfe4..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaCollisionPublisher.h +++ /dev/null @@ -1,45 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include - -#include "carla/geom/Vector3D.h" - -#include "carla/ros2/publishers/BasePublisher.h" -#include "carla/ros2/publishers/PublisherImpl.h" - -#include "carla/ros2/types/CarlaCollisionEvent.h" -#include "carla/ros2/types/CarlaCollisionEventPubSubTypes.h" - -namespace carla { -namespace ros2 { - - class CarlaCollisionPublisher : public BasePublisher { - public: - struct CollisionMsgTraits { - using msg_type = carla_msgs::msg::CarlaCollisionEvent; - using msg_pubsub_type = carla_msgs::msg::CarlaCollisionEventPubSubType; - }; - - CarlaCollisionPublisher(std::string base_topic_name, std::string frame_id) : - BasePublisher(base_topic_name, frame_id), - _impl(std::make_shared>()) { - _impl->Init(this->GetBaseTopicName()); - } - - bool Publish() { - return _impl->Publish(); - } - - bool Write(int32_t seconds, uint32_t nanoseconds, uint32_t actor_id, geom::Vector3D impulse); - - private: - std::shared_ptr> _impl; - }; - -} // namespace ros2 -} // namespace carla - diff --git a/LibCarla/source/carla/ros2/publishers/CarlaDVSPublisher.cpp b/LibCarla/source/carla/ros2/publishers/CarlaDVSPublisher.cpp deleted file mode 100644 index 6df3190d62e..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaDVSPublisher.cpp +++ /dev/null @@ -1,57 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "CarlaDVSPublisher.h" - -#include "carla/sensor/data/DVSEvent.h" - -namespace carla { -namespace ros2 { - -const size_t CarlaDVSPointCloudPublisher::GetPointSize() { - return sizeof(sensor::data::DVSEvent); -} - -std::vector CarlaDVSPointCloudPublisher::GetFields() { - - sensor_msgs::msg::PointField descriptor1; - descriptor1.name("x"); - descriptor1.offset(0); - descriptor1.datatype(sensor_msgs::msg::PointField__UINT16); - descriptor1.count(1); - sensor_msgs::msg::PointField descriptor2; - descriptor2.name("y"); - descriptor2.offset(2); - descriptor2.datatype(sensor_msgs::msg::PointField__UINT16); - descriptor2.count(1); - sensor_msgs::msg::PointField descriptor3; - descriptor3.name("t"); - descriptor3.offset(4); - descriptor3.datatype(sensor_msgs::msg::PointField__FLOAT64); - descriptor3.count(1); - sensor_msgs::msg::PointField descriptor4; - descriptor3.name("pol"); - descriptor3.offset(12); - descriptor3.datatype(sensor_msgs::msg::PointField__INT8); - descriptor3.count(1); - - return {descriptor1, descriptor2, descriptor3, descriptor4}; -} - -std::vector CarlaDVSPointCloudPublisher::ComputePointCloud(uint32_t height, uint32_t width, uint8_t *data) { - - sensor::data::DVSEvent* events = reinterpret_cast(data); - const size_t total_points = height * width; - for (size_t i = 0; i < total_points; ++i) { - events[i].y *= -1.0f; - } - - const size_t total_bytes = total_points * sizeof(sensor::data::DVSEvent); - std::vector vector_data(reinterpret_cast(events), - reinterpret_cast(events) + total_bytes); - return vector_data; -} - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaDVSPublisher.h b/LibCarla/source/carla/ros2/publishers/CarlaDVSPublisher.h deleted file mode 100644 index bb0ed58767d..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaDVSPublisher.h +++ /dev/null @@ -1,83 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include -#include -#include - -#include "carla/ros2/publishers/BasePublisher.h" - -#include "CarlaCameraPublisher.h" -#include "CarlaPointCloudPublisher.h" - -#include "carla/sensor/data/DVSEvent.h" - -namespace carla { -namespace ros2 { - - class CarlaDVSCameraPublisher : public CarlaCameraPublisher { - public: - CarlaDVSCameraPublisher(std::string base_topic_name, std::string frame_id): - CarlaCameraPublisher(base_topic_name, frame_id) {} - - uint8_t GetChannels() override { return 3; } - - private: - std::string GetEncoding() override { return "bgr8"; } - }; - - class CarlaDVSPointCloudPublisher : public CarlaPointCloudPublisher { - public: - CarlaDVSPointCloudPublisher(std::string base_topic_name, std::string frame_id): - CarlaPointCloudPublisher(base_topic_name, frame_id) {} - - private: - const size_t GetPointSize() override; - std::vector GetFields() override; - - std::vector ComputePointCloud(uint32_t height, uint32_t width, uint8_t *data) override; - }; - - class CarlaDVSPublisher : public BasePublisher { - public: - - CarlaDVSPublisher(std::string base_topic_name, std::string frame_id) : - BasePublisher(base_topic_name, frame_id) { - _camera_pub = std::make_shared(base_topic_name, frame_id); - _point_cloud_pub = std::make_shared(base_topic_name, frame_id); - } - - bool Publish() { - return _camera_pub->Publish() && _point_cloud_pub->Publish(); - } - - bool WriteCameraInfo(int32_t seconds, uint32_t nanoseconds, uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify) { - return _camera_pub->WriteCameraInfo(seconds, nanoseconds, x_offset, y_offset, height, width, fov, do_rectify); - } - bool WriteImage(int32_t seconds, uint32_t nanoseconds, uint32_t elements, uint32_t im_height, uint32_t im_width, const uint8_t *data) { - const size_t im_size = im_width * im_height * _camera_pub->GetChannels(); - std::vector im_data(im_size, 0); - - const carla::sensor::data::DVSEvent* events = reinterpret_cast(data); - for (size_t i = 0; i < elements; ++i) { - const auto& event = events[i]; - size_t index = (event.y * im_width + event.x) * 3 + (static_cast(event.pol) * 2); - im_data[index] = 255; - } - - return _camera_pub->WriteImage(seconds, nanoseconds, im_height, im_width, std::move(im_data)); - } - bool WritePointCloud(int32_t seconds, uint32_t nanoseconds, uint32_t height, uint32_t width, uint8_t* data) { - return _point_cloud_pub->WritePointCloud(seconds, nanoseconds, height, width, data); - } - - private: - std::shared_ptr _camera_pub; - std::shared_ptr _point_cloud_pub; - }; - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaDepthCameraPublisher.h b/LibCarla/source/carla/ros2/publishers/CarlaDepthCameraPublisher.h deleted file mode 100644 index 3bf1b894e87..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaDepthCameraPublisher.h +++ /dev/null @@ -1,15 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include "carla/ros2/publishers/CarlaRGBCameraPublisher.h" - -namespace carla { -namespace ros2 { - - using CarlaDepthCameraPublisher = CarlaRGBCameraPublisher; - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaGNSSPublisher.cpp b/LibCarla/source/carla/ros2/publishers/CarlaGNSSPublisher.cpp deleted file mode 100644 index bb79bb56fa8..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaGNSSPublisher.cpp +++ /dev/null @@ -1,24 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "CarlaGNSSPublisher.h" - -namespace carla { -namespace ros2 { - -bool CarlaGNSSPublisher::Write(int32_t seconds, uint32_t nanoseconds, const geom::GeoLocation data) { - - _impl->GetMessage()->header().stamp().sec(seconds); - _impl->GetMessage()->header().stamp().nanosec(nanoseconds); - _impl->GetMessage()->header().frame_id(GetFrameId()); - - _impl->GetMessage()->latitude(data.latitude); - _impl->GetMessage()->longitude(data.longitude); - _impl->GetMessage()->altitude(data.altitude); - - return true; -} - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaGNSSPublisher.h b/LibCarla/source/carla/ros2/publishers/CarlaGNSSPublisher.h deleted file mode 100644 index abcc0217ac6..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaGNSSPublisher.h +++ /dev/null @@ -1,44 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include - -#include "carla/geom/GeoLocation.h" - -#include "carla/ros2/publishers/BasePublisher.h" -#include "carla/ros2/publishers/PublisherImpl.h" - -#include "carla/ros2/types/NavSatFix.h" -#include "carla/ros2/types/NavSatFixPubSubTypes.h" - -namespace carla { -namespace ros2 { - - class CarlaGNSSPublisher : public BasePublisher { - public: - struct GnssMsgTraits { - using msg_type = sensor_msgs::msg::NavSatFix; - using msg_pubsub_type = sensor_msgs::msg::NavSatFixPubSubType; - }; - - CarlaGNSSPublisher(std::string base_topic_name, std::string frame_id): - BasePublisher(base_topic_name, frame_id), - _impl(std::make_shared>()) { - _impl->Init(this->GetBaseTopicName()); - } - - bool Publish() { - return _impl->Publish(); - } - - bool Write(int32_t seconds, uint32_t nanoseconds, const geom::GeoLocation data); - - private: - std::shared_ptr> _impl; - }; - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaIMUPublisher.cpp b/LibCarla/source/carla/ros2/publishers/CarlaIMUPublisher.cpp deleted file mode 100644 index 3a2afa170b7..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaIMUPublisher.cpp +++ /dev/null @@ -1,49 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "CarlaIMUPublisher.h" - -namespace carla { -namespace ros2 { - -bool CarlaIMUPublisher::Write(int32_t seconds, uint32_t nanoseconds, geom::Vector3D accelerometer, geom::Vector3D gyroscope, float compass) { - - _impl->GetMessage()->header().stamp().sec(seconds); - _impl->GetMessage()->header().stamp().nanosec(nanoseconds); - _impl->GetMessage()->header().frame_id(GetFrameId()); - - _impl->GetMessage()->linear_acceleration().x(accelerometer.x); - _impl->GetMessage()->linear_acceleration().y(-accelerometer.y); - _impl->GetMessage()->linear_acceleration().z(accelerometer.z); - - _impl->GetMessage()->angular_velocity().x(-gyroscope.x); - _impl->GetMessage()->angular_velocity().y(gyroscope.y); - _impl->GetMessage()->angular_velocity().z(-gyroscope.z); - - const float rx = 0.0f; // pitch - const float ry = (float(M_PI_2) / 2.0f) - compass; // yaw - const float rz = 0.0f; // roll - - const float cr = cosf(rz * 0.5f); - const float sr = sinf(rz * 0.5f); - const float cp = cosf(rx * 0.5f); - const float sp = sinf(rx * 0.5f); - const float cy = cosf(ry * 0.5f); - const float sy = sinf(ry * 0.5f); - - const float w = cr * cp * cy + sr * sp * sy; - const float x = sr * cp * cy - cr * sp * sy; - const float y = cr * sp * cy + sr * cp * sy; - const float z = cr * cp * sy - sr * sp * cy; - - _impl->GetMessage()->orientation().w(w); - _impl->GetMessage()->orientation().x(x); - _impl->GetMessage()->orientation().y(y); - _impl->GetMessage()->orientation().z(z); - - return true; -} - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaIMUPublisher.h b/LibCarla/source/carla/ros2/publishers/CarlaIMUPublisher.h deleted file mode 100644 index e9d70472ed3..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaIMUPublisher.h +++ /dev/null @@ -1,44 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include - -#include "carla/geom/Vector3D.h" - -#include "carla/ros2/publishers/BasePublisher.h" -#include "carla/ros2/publishers/PublisherImpl.h" - -#include "carla/ros2/types/Imu.h" -#include "carla/ros2/types/ImuPubSubTypes.h" - -namespace carla { -namespace ros2 { - - class CarlaIMUPublisher : public BasePublisher { - public: - struct ImuMsgTraits { - using msg_type = sensor_msgs::msg::Imu; - using msg_pubsub_type = sensor_msgs::msg::ImuPubSubType; - }; - - CarlaIMUPublisher(std::string base_topic_name, std::string frame_id) : - BasePublisher(base_topic_name, frame_id), - _impl(std::make_shared>()) { - _impl->Init(this->GetBaseTopicName()); - } - - bool Publish() { - return _impl->Publish(); - } - - bool Write(int32_t seconds, uint32_t nanoseconds, geom::Vector3D accelerometer, geom::Vector3D gyroscope, float compass); - - private: - std::shared_ptr> _impl; - }; - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaISCameraPublisher.h b/LibCarla/source/carla/ros2/publishers/CarlaISCameraPublisher.h deleted file mode 100644 index 379ac1a868d..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaISCameraPublisher.h +++ /dev/null @@ -1,15 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include "carla/ros2/publishers/CarlaRGBCameraPublisher.h" - -namespace carla { -namespace ros2 { - - using CarlaISCameraPublisher = CarlaRGBCameraPublisher; - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaLidarPublisher.cpp b/LibCarla/source/carla/ros2/publishers/CarlaLidarPublisher.cpp deleted file mode 100644 index 3a9fec01b56..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaLidarPublisher.cpp +++ /dev/null @@ -1,61 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "CarlaLidarPublisher.h" - -#include "carla/sensor/data/LidarData.h" - -namespace carla { -namespace ros2 { - -const size_t CarlaLidarPublisher::GetPointSize() { - return sizeof(sensor::data::LidarDetection); -} - -std::vector CarlaLidarPublisher::GetFields() { - - sensor_msgs::msg::PointField descriptor1; - descriptor1.name("x"); - descriptor1.offset(0); - descriptor1.datatype(sensor_msgs::msg::PointField__FLOAT32); - descriptor1.count(1); - - sensor_msgs::msg::PointField descriptor2; - descriptor2.name("y"); - descriptor2.offset(4); - descriptor2.datatype(sensor_msgs::msg::PointField__FLOAT32); - descriptor2.count(1); - - sensor_msgs::msg::PointField descriptor3; - descriptor3.name("z"); - descriptor3.offset(8); - descriptor3.datatype(sensor_msgs::msg::PointField__FLOAT32); - descriptor3.count(1); - - sensor_msgs::msg::PointField descriptor4; - descriptor4.name("intensity"); - descriptor4.offset(12); - descriptor4.datatype(sensor_msgs::msg::PointField__FLOAT32); - descriptor4.count(1); - - return {descriptor1, descriptor2, descriptor3, descriptor4}; -} - -std::vector CarlaLidarPublisher::ComputePointCloud(uint32_t height, uint32_t width, uint8_t *data) { - - sensor::data::LidarDetection* detections = reinterpret_cast(data); - - const size_t total_points = height * width; - for (size_t i = 0; i < total_points; ++i) { - detections[i].point.y *= -1.0f; - } - - const size_t total_bytes = total_points * sizeof(sensor::data::LidarDetection); - std::vector vector_data(reinterpret_cast(detections), - reinterpret_cast(detections) + total_bytes); - return vector_data; -} - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaLidarPublisher.h b/LibCarla/source/carla/ros2/publishers/CarlaLidarPublisher.h deleted file mode 100644 index d8a7e923c39..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaLidarPublisher.h +++ /dev/null @@ -1,27 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include - -#include "CarlaPointCloudPublisher.h" - -namespace carla { -namespace ros2 { - - class CarlaLidarPublisher : public CarlaPointCloudPublisher { - public: - CarlaLidarPublisher(std::string base_topic_name, std::string frame_id) : - CarlaPointCloudPublisher(base_topic_name, frame_id) {} - - private: - const size_t GetPointSize() override; - std::vector GetFields() override; - - std::vector ComputePointCloud(uint32_t height, uint32_t width, uint8_t *data) override; - }; - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaNormalsCameraPublisher.h b/LibCarla/source/carla/ros2/publishers/CarlaNormalsCameraPublisher.h deleted file mode 100644 index 96d3adb0fa7..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaNormalsCameraPublisher.h +++ /dev/null @@ -1,15 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include "carla/ros2/publishers/CarlaRGBCameraPublisher.h" - -namespace carla { -namespace ros2 { - - using CarlaNormalsCameraPublisher = CarlaRGBCameraPublisher; - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaOpticalFlowCameraPublisher.h b/LibCarla/source/carla/ros2/publishers/CarlaOpticalFlowCameraPublisher.h deleted file mode 100644 index d66a7712153..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaOpticalFlowCameraPublisher.h +++ /dev/null @@ -1,15 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include "carla/ros2/publishers/CarlaRGBCameraPublisher.h" - -namespace carla { -namespace ros2 { - - using CarlaOpticalFlowCameraPublisher = CarlaRGBCameraPublisher; - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaPointCloudPublisher.cpp b/LibCarla/source/carla/ros2/publishers/CarlaPointCloudPublisher.cpp deleted file mode 100644 index 8e51a8a3b09..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaPointCloudPublisher.cpp +++ /dev/null @@ -1,32 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "CarlaPointCloudPublisher.h" - -namespace carla { -namespace ros2 { - -bool CarlaPointCloudPublisher::WritePointCloud(int32_t seconds, uint32_t nanoseconds, uint32_t height, uint32_t width, std::vector data) { - - _impl->GetMessage()->header().stamp().sec(seconds); - _impl->GetMessage()->header().stamp().nanosec(nanoseconds); - _impl->GetMessage()->header().frame_id(GetFrameId()); - - auto fields = GetFields(); - const size_t point_size = GetPointSize(); - - _impl->GetMessage()->width(width); - _impl->GetMessage()->height(height); - _impl->GetMessage()->is_bigendian(false); - _impl->GetMessage()->fields(fields); - _impl->GetMessage()->point_step(point_size); - _impl->GetMessage()->row_step(width * point_size); - _impl->GetMessage()->is_dense(false); // True if there are not invalid points - _impl->GetMessage()->data(std::move(data)); - - return true; -} - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaPointCloudPublisher.h b/LibCarla/source/carla/ros2/publishers/CarlaPointCloudPublisher.h deleted file mode 100644 index b8b27d1a816..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaPointCloudPublisher.h +++ /dev/null @@ -1,53 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include -#include - -#include "carla/ros2/publishers/BasePublisher.h" -#include "carla/ros2/publishers/PublisherImpl.h" - -#include "carla/ros2/types/PointCloud2.h" -#include "carla/ros2/types/PointCloud2PubSubTypes.h" - -namespace carla { -namespace ros2 { - - class CarlaPointCloudPublisher : public BasePublisher { - public: - struct PointCloudMsgTraits { - using msg_type = sensor_msgs::msg::PointCloud2; - using msg_pubsub_type = sensor_msgs::msg::PointCloud2PubSubType; - }; - - CarlaPointCloudPublisher(std::string base_topic_name, std::string frame_id) : - BasePublisher(base_topic_name, frame_id), - _impl(std::make_shared>()) { - _impl->Init(GetBaseTopicName() + "/point_cloud"); - } - - bool Publish() { - return _impl->Publish(); - } - - bool WritePointCloud(int32_t seconds, uint32_t nanoseconds, uint32_t height, uint32_t width, uint8_t* data) { - return WritePointCloud(seconds, nanoseconds, height, width, ComputePointCloud(height, width, data)); - } - bool WritePointCloud(int32_t seconds, uint32_t nanoseconds, uint32_t height, uint32_t width, std::vector data); - - private: - virtual const size_t GetPointSize() = 0; - virtual std::vector GetFields() = 0; - - virtual std::vector ComputePointCloud(uint32_t height, uint32_t width, uint8_t *data) = 0; - - - private: - std::shared_ptr> _impl; - }; - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaRGBCameraPublisher.h b/LibCarla/source/carla/ros2/publishers/CarlaRGBCameraPublisher.h deleted file mode 100644 index 3eead95ebc3..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaRGBCameraPublisher.h +++ /dev/null @@ -1,24 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include "carla/ros2/publishers/CarlaCameraPublisher.h" - -namespace carla { -namespace ros2 { - -class CarlaRGBCameraPublisher : public CarlaCameraPublisher { - public: - CarlaRGBCameraPublisher(std::string base_topic_name, std::string frame_id): - CarlaCameraPublisher(base_topic_name, frame_id) {} - - uint8_t GetChannels() override { return 4; } - - private: - std::string GetEncoding() override { return "bgra8"; } -}; - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaRadarPublisher.cpp b/LibCarla/source/carla/ros2/publishers/CarlaRadarPublisher.cpp deleted file mode 100644 index 0670464130b..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaRadarPublisher.cpp +++ /dev/null @@ -1,92 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "CarlaRadarPublisher.h" - -#include "carla/sensor/data/RadarData.h" - -namespace carla { -namespace ros2 { - -struct RadarDetectionWithPosition { - float x; - float y; - float z; - carla::sensor::data::RadarDetection detection; -}; - -const size_t CarlaRadarPublisher::GetPointSize() { - return sizeof(RadarDetectionWithPosition); -} - -std::vector CarlaRadarPublisher::GetFields() { - - sensor_msgs::msg::PointField descriptor1; - descriptor1.name("x"); - descriptor1.offset(0); - descriptor1.datatype(sensor_msgs::msg::PointField__FLOAT32); - descriptor1.count(1); - - sensor_msgs::msg::PointField descriptor2; - descriptor2.name("y"); - descriptor2.offset(4); - descriptor2.datatype(sensor_msgs::msg::PointField__FLOAT32); - descriptor2.count(1); - - sensor_msgs::msg::PointField descriptor3; - descriptor3.name("z"); - descriptor3.offset(8); - descriptor3.datatype(sensor_msgs::msg::PointField__FLOAT32); - descriptor3.count(1); - - sensor_msgs::msg::PointField descriptor4; - descriptor4.name("velocity"); - descriptor4.offset(12); - descriptor4.datatype(sensor_msgs::msg::PointField__FLOAT32); - descriptor4.count(1); - - sensor_msgs::msg::PointField descriptor5; - descriptor5.name("azimuth"); - descriptor5.offset(16); - descriptor5.datatype(sensor_msgs::msg::PointField__FLOAT32); - descriptor5.count(1); - - sensor_msgs::msg::PointField descriptor6; - descriptor6.name("altitude"); - descriptor6.offset(20); - descriptor6.datatype(sensor_msgs::msg::PointField__FLOAT32); - descriptor6.count(1); - - sensor_msgs::msg::PointField descriptor7; - descriptor7.name("depth"); - descriptor7.offset(24); - descriptor7.datatype(sensor_msgs::msg::PointField__FLOAT32); - descriptor7.count(1); - - return {descriptor1, descriptor2, descriptor3, descriptor4, descriptor5, descriptor6, descriptor7}; -} - -std::vector CarlaRadarPublisher::ComputePointCloud(uint32_t height, uint32_t width, uint8_t *data) { - - carla::sensor::data::RadarDetection* detections = reinterpret_cast(data); - const size_t total_bytes = height * width * sizeof(sensor::data::RadarDetection); - const size_t total_points = total_bytes / sizeof(sensor::data::RadarDetection); - - std::vector radar_points(total_points); - for (size_t i = 0; i < total_points; ++i) { - const auto& det = detections[i]; - auto& point = radar_points[i]; - - point.x = det.depth * std::cos(det.azimuth) * std::cos(-det.altitude); - point.y = det.depth * std::sin(-det.azimuth) * std::cos(det.altitude); - point.z = det.depth * std::sin(det.altitude); - point.detection = det; - } - - const uint8_t* byte_ptr = reinterpret_cast(radar_points.data()); - return std::vector(byte_ptr, byte_ptr + radar_points.size() * sizeof(RadarDetectionWithPosition)); -} - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaRadarPublisher.h b/LibCarla/source/carla/ros2/publishers/CarlaRadarPublisher.h deleted file mode 100644 index 402046eb2da..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaRadarPublisher.h +++ /dev/null @@ -1,27 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include -#include - -#include "CarlaPointCloudPublisher.h" - -namespace carla { -namespace ros2 { - - class CarlaRadarPublisher : public CarlaPointCloudPublisher { - public: - CarlaRadarPublisher(std::string base_topic_name, std::string frame_id) : - CarlaPointCloudPublisher(base_topic_name, frame_id) {} - - private: - const size_t GetPointSize() override; - std::vector GetFields() override; - - std::vector ComputePointCloud(uint32_t height, uint32_t width, uint8_t *data) override; - }; -} -} diff --git a/LibCarla/source/carla/ros2/publishers/CarlaSSCameraPublisher.h b/LibCarla/source/carla/ros2/publishers/CarlaSSCameraPublisher.h deleted file mode 100644 index 202f53a002e..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaSSCameraPublisher.h +++ /dev/null @@ -1,15 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include "carla/ros2/publishers/CarlaRGBCameraPublisher.h" - -namespace carla { -namespace ros2 { - - using CarlaSSCameraPublisher = CarlaRGBCameraPublisher; - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaSemanticLidarPublisher.cpp b/LibCarla/source/carla/ros2/publishers/CarlaSemanticLidarPublisher.cpp deleted file mode 100644 index 256f3d8171a..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaSemanticLidarPublisher.cpp +++ /dev/null @@ -1,73 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "CarlaSemanticLidarPublisher.h" - -#include "carla/sensor/data/SemanticLidarData.h" - -namespace carla { -namespace ros2 { - -const size_t CarlaSemanticLidarPublisher::GetPointSize() { - return sizeof(sensor::data::SemanticLidarDetection); -} - -std::vector CarlaSemanticLidarPublisher::GetFields() { - - sensor_msgs::msg::PointField descriptor1; - descriptor1.name("x"); - descriptor1.offset(0); - descriptor1.datatype(sensor_msgs::msg::PointField__FLOAT32); - descriptor1.count(1); - - sensor_msgs::msg::PointField descriptor2; - descriptor2.name("y"); - descriptor2.offset(4); - descriptor2.datatype(sensor_msgs::msg::PointField__FLOAT32); - descriptor2.count(1); - - sensor_msgs::msg::PointField descriptor3; - descriptor3.name("z"); - descriptor3.offset(8); - descriptor3.datatype(sensor_msgs::msg::PointField__FLOAT32); - descriptor3.count(1); - - sensor_msgs::msg::PointField descriptor4; - descriptor4.name("cos_inc_angle"); - descriptor4.offset(12); - descriptor4.datatype(sensor_msgs::msg::PointField__FLOAT32); - descriptor4.count(1); - - sensor_msgs::msg::PointField descriptor5; - descriptor5.name("object_idx"); - descriptor5.offset(16); - descriptor5.datatype(sensor_msgs::msg::PointField__UINT32); - descriptor5.count(1); - - sensor_msgs::msg::PointField descriptor6; - descriptor6.name("object_tag"); - descriptor6.offset(20); - descriptor6.datatype(sensor_msgs::msg::PointField__UINT32); - descriptor6.count(1); - - return {descriptor1, descriptor2, descriptor3, descriptor4, descriptor5, descriptor6}; -} - -std::vector CarlaSemanticLidarPublisher::ComputePointCloud(uint32_t height, uint32_t width, uint8_t *data) { - - sensor::data::SemanticLidarDetection* detections = reinterpret_cast(data); - - const size_t total_points = height * width; - for (size_t i = 0; i < total_points; ++i) { - detections[i].point.y *= -1.0f; - } - - const size_t total_bytes = total_points * sizeof(sensor::data::SemanticLidarDetection); - std::vector vector_data(reinterpret_cast(detections), - reinterpret_cast(detections) + total_bytes); - return vector_data; -} - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaSemanticLidarPublisher.h b/LibCarla/source/carla/ros2/publishers/CarlaSemanticLidarPublisher.h deleted file mode 100644 index 5959771c4cd..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaSemanticLidarPublisher.h +++ /dev/null @@ -1,27 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include -#include - -#include "CarlaPointCloudPublisher.h" - -namespace carla { -namespace ros2 { - - class CarlaSemanticLidarPublisher : public CarlaPointCloudPublisher { - public: - CarlaSemanticLidarPublisher(std::string base_topic_name, std::string frame_id) : - CarlaPointCloudPublisher(base_topic_name, frame_id) {} - - private: - const size_t GetPointSize() override; - std::vector GetFields() override; - - std::vector ComputePointCloud(uint32_t height, uint32_t width, uint8_t *data) override; - }; -} -} diff --git a/LibCarla/source/carla/ros2/publishers/CarlaStatusPublisher.cpp b/LibCarla/source/carla/ros2/publishers/CarlaStatusPublisher.cpp new file mode 100644 index 00000000000..3470475fa7d --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/CarlaStatusPublisher.cpp @@ -0,0 +1,37 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "CarlaStatusPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +CarlaStatusPublisher::CarlaStatusPublisher() + : PublisherBaseSensor(carla::ros2::types::ActorNameDefinition::CreateFromRoleName("status")), + _impl(std::make_shared()) {} + +bool CarlaStatusPublisher::Init(std::shared_ptr domain_participant) { + // provide the status transient local to ensure if CARLA is stuck and someone wants to query the synchronization status, + // then the last published state is still available and one is able to detect for what CARLA is waiting + auto topic_qos = get_topic_qos(); + topic_qos.transient_local(); + return _impl->Init(domain_participant, get_topic_name(), topic_qos); +} + +bool CarlaStatusPublisher::Publish() { + return _impl->Publish(); +} + +bool CarlaStatusPublisher::SubscribersConnected() const { + return _impl->SubscribersConnected(); +} + +void CarlaStatusPublisher::UpdateCarlaStatus(const carla_msgs::msg::CarlaStatus& status) { + _impl->Message() = status; + _impl->SetMessageUpdated(); +} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaStatusPublisher.h b/LibCarla/source/carla/ros2/publishers/CarlaStatusPublisher.h new file mode 100644 index 00000000000..4d27f58eb87 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/CarlaStatusPublisher.h @@ -0,0 +1,40 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/PublisherBaseSensor.h" +#include "carla_msgs/msg/CarlaStatusPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using CarlaStatusPublisherImpl = DdsPublisherImpl; + +class CarlaStatusPublisher : public PublisherBaseSensor { +public: + CarlaStatusPublisher(); + virtual ~CarlaStatusPublisher() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + void UpdateCarlaStatus(const carla_msgs::msg::CarlaStatus& status); + +private: + std::shared_ptr _impl; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaTransformPublisher.cpp b/LibCarla/source/carla/ros2/publishers/CarlaTransformPublisher.cpp deleted file mode 100644 index 6fc05aa0966..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaTransformPublisher.cpp +++ /dev/null @@ -1,88 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "CarlaTransformPublisher.h" - -namespace carla { -namespace ros2 { - -constexpr double EPSILON = 1e-4; - -geometry_msgs::msg::Transform CarlaTransformPublisher::ComputeTransform(std::string frame_id, geom::Transform transform) { - - // Avoid recomputing the transform if it hasn't changed. - // This is common for static sensors that are typically attached to other actors. - auto it = _last_transforms.find(frame_id); - if (it != _last_transforms.end()) { - const auto& [last_transform, last_tf] = it->second; - - // Do not use operator== directly on transforms. - // Floating-point errors can cause two transforms that are equal to compare as different. - if (std::abs(last_transform.location.x - transform.location.x) < EPSILON - && std::abs(last_transform.location.y - transform.location.y) < EPSILON - && std::abs(last_transform.location.z - transform.location.z) < EPSILON - && std::abs(last_transform.rotation.roll - transform.rotation.roll) < EPSILON - && std::abs(last_transform.rotation.pitch - transform.rotation.pitch) < EPSILON - && std::abs(last_transform.rotation.yaw - transform.rotation.yaw) < EPSILON - ) { - return last_tf; - } - } - - // Better readability - const float tx = transform.location.x; - const float ty = transform.location.y * -1.0f; - const float tz = transform.location.z; - - // Rotations was not correctly computed Radians = Degrees * (π / 180) - const float DEG_TO_RAD = float(M_PI) / 180.0f; - const float rx = (transform.rotation.pitch * -1.0f) * DEG_TO_RAD; - const float ry = (transform.rotation.yaw * -1.0f) * DEG_TO_RAD; - const float rz = transform.rotation.roll * DEG_TO_RAD; - - const float cr = cosf(rz * 0.5f); - const float sr = sinf(rz * 0.5f); - const float cp = cosf(rx * 0.5f); - const float sp = sinf(rx * 0.5f); - const float cy = cosf(ry * 0.5f); - const float sy = sinf(ry * 0.5f); - - geometry_msgs::msg::Transform tf; - - tf.translation().x(tx); - tf.translation().y(ty); - tf.translation().z(tz); - - tf.rotation().w(cr * cp * cy + sr * sp * sy); - tf.rotation().x(sr * cp * cy - cr * sp * sy); - tf.rotation().y(cr * sp * cy + sr * cp * sy); - tf.rotation().z(cr * cp * sy - sr * sp * cy); - - return tf; -} - -bool CarlaTransformPublisher::Write(int32_t seconds, uint32_t nanoseconds, std::string frame_id, std::string child_frame_id, geom::Transform transform) { - - - geometry_msgs::msg::TransformStamped ts; - - ts.header().stamp().sec(seconds); - ts.header().stamp().nanosec(nanoseconds); - ts.header().frame_id(frame_id); - - auto tf = ComputeTransform(child_frame_id, transform); - ts.transform(tf); - - ts.child_frame_id(child_frame_id); - - _impl->GetMessage()->transforms({ts}); - - // Update last transform information - _last_transforms.insert({child_frame_id, {transform, tf}}); - - return true; -} - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/CarlaTransformPublisher.h b/LibCarla/source/carla/ros2/publishers/CarlaTransformPublisher.h deleted file mode 100644 index 82bbe9125c8..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaTransformPublisher.h +++ /dev/null @@ -1,50 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include -#include - -#include "carla/geom/Transform.h" - -#include "carla/ros2/publishers/BasePublisher.h" -#include "carla/ros2/publishers/PublisherImpl.h" - -#include "carla/ros2/types/TFMessage.h" -#include "carla/ros2/types/TFMessagePubSubTypes.h" - -namespace carla { -namespace ros2 { - - class CarlaTransformPublisher : public BasePublisher { - public: - struct TransformMsgTraits { - using msg_type = tf2_msgs::msg::TFMessage; - using msg_pubsub_type = tf2_msgs::msg::TFMessagePubSubType; - }; - - CarlaTransformPublisher() : - BasePublisher("rt/tf"), - _impl(std::make_shared>()) { - _impl->Init(GetBaseTopicName()); - } - - bool Publish() { - return _impl->Publish(); - } - - bool Write(int32_t seconds, uint32_t nanoseconds, std::string frame_id, std::string child_frame_id, geom::Transform transform); - - private: - geometry_msgs::msg::Transform ComputeTransform(std::string frame_id, geom::Transform current_transform); - - private: - std::shared_ptr> _impl; - - std::unordered_map> _last_transforms; - }; - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/ClockPublisher.cpp b/LibCarla/source/carla/ros2/publishers/ClockPublisher.cpp new file mode 100644 index 00000000000..ca834079f65 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/ClockPublisher.cpp @@ -0,0 +1,33 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "ClockPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +ClockPublisher::ClockPublisher() + : PublisherBase(carla::ros2::types::ActorNameDefinition::CreateFromRoleName("clock")), + _impl(std::make_shared()) {} + +bool ClockPublisher::Init(std::shared_ptr domain_participant) { + return _impl->Init(domain_participant, "rt/clock", get_topic_qos()); +} + +bool ClockPublisher::Publish() { + return _impl->Publish(); +} + +bool ClockPublisher::SubscribersConnected() const { + return _impl->SubscribersConnected(); +} + +void ClockPublisher::UpdateData(const builtin_interfaces::msg::Time &stamp) { + _impl->Message().clock(stamp); + _impl->SetMessageUpdated(); +} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/ClockPublisher.h b/LibCarla/source/carla/ros2/publishers/ClockPublisher.h new file mode 100644 index 00000000000..798cf5e20d6 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/ClockPublisher.h @@ -0,0 +1,44 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/PublisherBase.h" +#include "rosgraph_msgs/msg/ClockPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using ClockPublisherImpl = DdsPublisherImpl; + +class ClockPublisher : public PublisherBase { +public: + ClockPublisher(); + virtual ~ClockPublisher() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + + /** + * Implement PublisherInterface::SubscribersConnected() interface + */ + bool SubscribersConnected() const override; + + /** + * UpdateData() + */ + void UpdateData(const builtin_interfaces::msg::Time &stamp); + +private: + std::shared_ptr _impl; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/MapPublisher.cpp b/LibCarla/source/carla/ros2/publishers/MapPublisher.cpp new file mode 100644 index 00000000000..3ddb49fc2e7 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/MapPublisher.cpp @@ -0,0 +1,33 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "MapPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +MapPublisher::MapPublisher() + : PublisherBase(carla::ros2::types::ActorNameDefinition::CreateFromRoleName("map")), + _impl(std::make_shared()) {} + +bool MapPublisher::Init(std::shared_ptr domain_participant) { + return _impl->InitHistoryPreallocatedWithReallocMemoryMode(domain_participant, get_topic_name(), get_topic_qos()); +} + +bool MapPublisher::Publish() { + return _impl->Publish(); +} + +bool MapPublisher::SubscribersConnected() const { + return _impl->SubscribersConnected(); +} + +void MapPublisher::UpdateData(std::string const &data) { + _impl->Message().data(data); + _impl->SetMessageUpdated(); +} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/MapPublisher.h b/LibCarla/source/carla/ros2/publishers/MapPublisher.h new file mode 100644 index 00000000000..3b2f7a948ad --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/MapPublisher.h @@ -0,0 +1,42 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include + +#include "carla/ros2/publishers/PublisherBase.h" +#include "std_msgs/msg/StringPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using MapPublisherImpl = DdsPublisherImpl; + +class MapPublisher : public PublisherBase { +public: + MapPublisher(); + virtual ~MapPublisher() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + void UpdateData(std::string const &data); + +private: + std::shared_ptr _impl; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/ObjectPublisher.cpp b/LibCarla/source/carla/ros2/publishers/ObjectPublisher.cpp new file mode 100644 index 00000000000..b66e03b5761 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/ObjectPublisher.cpp @@ -0,0 +1,39 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "ObjectPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +ObjectPublisher::ObjectPublisher(ROS2NameRecord &parent_publisher, std::shared_ptr objects_publisher) + : _parent_publisher(parent_publisher), + _impl(std::make_shared()), + _objects_publisher(objects_publisher) {} + +bool ObjectPublisher::Init(std::shared_ptr domain_participant) { + return _impl->InitHistoryPreallocatedWithReallocMemoryMode( + domain_participant, _parent_publisher.get_topic_name("object"), DEFAULT_SENSOR_DATA_QOS); +} + +bool ObjectPublisher::Publish() { + return _impl->Publish(); +} + +bool ObjectPublisher::SubscribersConnected() const { + return _impl->SubscribersConnected(); +} + +void ObjectPublisher::UpdateObject(std::shared_ptr &object) { + // forward the data to the objects publisher + _objects_publisher->AddObject(object); + derived_object_msgs::msg::Object ros_object = object->object(); + _impl->Message() = ros_object; + _impl->SetMessageHeader(ros_object.header().stamp(), _parent_publisher.frame_id()); +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/ObjectPublisher.h b/LibCarla/source/carla/ros2/publishers/ObjectPublisher.h new file mode 100644 index 00000000000..9e84f627128 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/ObjectPublisher.h @@ -0,0 +1,45 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/ObjectsPublisher.h" +#include "carla/ros2/publishers/PublisherInterface.h" +#include "carla/ros2/types/Object.h" +#include "derived_object_msgs/msg/ObjectPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using ObjectPublisherImpl = + DdsPublisherImpl; + +class ObjectPublisher : public PublisherInterface { +public: + ObjectPublisher(ROS2NameRecord &parent_publisher, std::shared_ptr objects_publisher); + virtual ~ObjectPublisher() = default; + + /** + * Implements Init() function + */ + bool Init(std::shared_ptr domain_participant); + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + void UpdateObject(std::shared_ptr &object); + +private: + ROS2NameRecord &_parent_publisher; + std::shared_ptr _impl; + std::shared_ptr _objects_publisher; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/ObjectWithCovariancePublisher.cpp b/LibCarla/source/carla/ros2/publishers/ObjectWithCovariancePublisher.cpp new file mode 100644 index 00000000000..de1cd2496b1 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/ObjectWithCovariancePublisher.cpp @@ -0,0 +1,39 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "ObjectWithCovariancePublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +ObjectWithCovariancePublisher::ObjectWithCovariancePublisher(ROS2NameRecord &parent_publisher, std::shared_ptr objects_publisher) + : _parent_publisher(parent_publisher), + _impl(std::make_shared()), + _objects_publisher(objects_publisher) {} + +bool ObjectWithCovariancePublisher::Init(std::shared_ptr domain_participant) { + return _impl->InitHistoryPreallocatedWithReallocMemoryMode( + domain_participant, _parent_publisher.get_topic_name("object_with_covariance"), DEFAULT_SENSOR_DATA_QOS); +} + +bool ObjectWithCovariancePublisher::Publish() { + return _impl->Publish(); +} + +bool ObjectWithCovariancePublisher::SubscribersConnected() const { + return _impl->SubscribersConnected(); +} + +void ObjectWithCovariancePublisher::UpdateObject(std::shared_ptr &object) { + // forward the data to the objects publisher + _objects_publisher->AddObject(object); + derived_object_msgs::msg::ObjectWithCovariance ros_object_with_covariance = object->object_with_covariance(); + _impl->Message() = ros_object_with_covariance; + _impl->SetMessageHeader(ros_object_with_covariance.header().stamp(), _parent_publisher.frame_id()); +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/ObjectWithCovariancePublisher.h b/LibCarla/source/carla/ros2/publishers/ObjectWithCovariancePublisher.h new file mode 100644 index 00000000000..7429b059cac --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/ObjectWithCovariancePublisher.h @@ -0,0 +1,45 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/ObjectsWithCovariancePublisher.h" +#include "carla/ros2/publishers/PublisherInterface.h" +#include "carla/ros2/types/Object.h" +#include "derived_object_msgs/msg/ObjectWithCovariancePubSubTypes.h" + +namespace carla { +namespace ros2 { + +using ObjectWithCovariancePublisherImpl = + DdsPublisherImpl; + +class ObjectWithCovariancePublisher : public PublisherInterface { +public: + ObjectWithCovariancePublisher(ROS2NameRecord &parent_publisher, std::shared_ptr objects_publisher); + virtual ~ObjectWithCovariancePublisher() = default; + + /** + * Implements Init() function + */ + bool Init(std::shared_ptr domain_participant); + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + void UpdateObject(std::shared_ptr &object); + +private: + ROS2NameRecord &_parent_publisher; + std::shared_ptr _impl; + std::shared_ptr _objects_publisher; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/ObjectsPublisher.cpp b/LibCarla/source/carla/ros2/publishers/ObjectsPublisher.cpp new file mode 100644 index 00000000000..97e47f4da9a --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/ObjectsPublisher.cpp @@ -0,0 +1,40 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "ObjectsPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +ObjectsPublisher::ObjectsPublisher() + : PublisherBaseSensor(carla::ros2::types::ActorNameDefinition::CreateFromRoleName("objects")), + _impl(std::make_shared()) {} + +bool ObjectsPublisher::Init(std::shared_ptr domain_participant) { + return _impl->InitHistoryPreallocatedWithReallocMemoryMode(domain_participant, get_topic_name(), get_topic_qos()); +} + +bool ObjectsPublisher::Publish() { + bool result = _impl->Publish(); + _impl->Message().objects().clear(); + return result; +} + +bool ObjectsPublisher::SubscribersConnected() const { + return _impl->SubscribersConnected(); +} + +void ObjectsPublisher::UpdateHeader(const builtin_interfaces::msg::Time &stamp) { + _impl->SetMessageHeader(stamp, "map"); +} + +void ObjectsPublisher::AddObject(std::shared_ptr &object) { + derived_object_msgs::msg::Object ros_object = object->object(); + _impl->Message().objects().emplace_back(ros_object); +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/ObjectsPublisher.h b/LibCarla/source/carla/ros2/publishers/ObjectsPublisher.h new file mode 100644 index 00000000000..539e50f9303 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/ObjectsPublisher.h @@ -0,0 +1,44 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/PublisherBaseSensor.h" +#include "carla/ros2/types/Object.h" +#include "derived_object_msgs/msg/ObjectArrayPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using ObjectsPublisherImpl = + DdsPublisherImpl; + +class ObjectsPublisher : public PublisherBaseSensor { +public: + ObjectsPublisher(); + virtual ~ObjectsPublisher() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + void UpdateHeader(const builtin_interfaces::msg::Time &stamp); + + void AddObject(std::shared_ptr &object); + +private: + std::shared_ptr _impl; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/ObjectsWithCovariancePublisher.cpp b/LibCarla/source/carla/ros2/publishers/ObjectsWithCovariancePublisher.cpp new file mode 100644 index 00000000000..34b3e1e5b15 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/ObjectsWithCovariancePublisher.cpp @@ -0,0 +1,40 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "ObjectsWithCovariancePublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +ObjectsWithCovariancePublisher::ObjectsWithCovariancePublisher() + : PublisherBaseSensor(carla::ros2::types::ActorNameDefinition::CreateFromRoleName("objects_with_covariance")), + _impl(std::make_shared()) {} + +bool ObjectsWithCovariancePublisher::Init(std::shared_ptr domain_participant) { + return _impl->InitHistoryPreallocatedWithReallocMemoryMode(domain_participant, get_topic_name(), get_topic_qos()); +} + +bool ObjectsWithCovariancePublisher::Publish() { + bool result = _impl->Publish(); + _impl->Message().objects().clear(); + return result; +} + +bool ObjectsWithCovariancePublisher::SubscribersConnected() const { + return _impl->SubscribersConnected(); +} + +void ObjectsWithCovariancePublisher::UpdateHeader(const builtin_interfaces::msg::Time &stamp) { + _impl->SetMessageHeader(stamp, "map"); +} + +void ObjectsWithCovariancePublisher::AddObject(std::shared_ptr &object) { + derived_object_msgs::msg::ObjectWithCovariance ros_object_with_covariance = object->object_with_covariance(); + _impl->Message().objects().emplace_back(ros_object_with_covariance); +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/ObjectsWithCovariancePublisher.h b/LibCarla/source/carla/ros2/publishers/ObjectsWithCovariancePublisher.h new file mode 100644 index 00000000000..2d33c93e546 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/ObjectsWithCovariancePublisher.h @@ -0,0 +1,44 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/PublisherBaseSensor.h" +#include "carla/ros2/types/Object.h" +#include "derived_object_msgs/msg/ObjectWithCovarianceArrayPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using ObjectsWithCovariancePublisherImpl = + DdsPublisherImpl; + +class ObjectsWithCovariancePublisher : public PublisherBaseSensor { +public: + ObjectsWithCovariancePublisher(); + virtual ~ObjectsWithCovariancePublisher() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + void UpdateHeader(const builtin_interfaces::msg::Time &stamp); + + void AddObject(std::shared_ptr &object); + +private: + std::shared_ptr _impl; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/PublisherBase.h b/LibCarla/source/carla/ros2/publishers/PublisherBase.h new file mode 100644 index 00000000000..9a2143ed8e5 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/PublisherBase.h @@ -0,0 +1,73 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/ROS2NameRecord.h" +#include "carla/ros2/ROS2QoS.h" +#include "carla/ros2/publishers/PublisherInterface.h" + +namespace carla { +namespace ros2 { + +template +class DdsPublisherImpl; + +/** + A Publisher base class for general publisher using default publishing qos. + Use this class for publisher that need a transform conversion for the TF tree in addition. + */ +class PublisherBase : public PublisherInterface, public ROS2NameRecord { +public: + PublisherBase(std::shared_ptr actor_name_definition) + : ROS2NameRecord(actor_name_definition) {} + virtual ~PublisherBase() = default; + + /** + * Initialze the publisher + */ + virtual bool Init(std::shared_ptr domain_participant) = 0; + + /* + * @brief Default get_topic_qos() for publishers + * + * Be aware: The default selection for publishers is NOT as done default in ROS2 (which aims compatibility to ROS1)! + * Per default, we want to achieve the most compatible combination within ROS2 world in the sense, + * that receiption is possible for all possible subscriber configurations. + * https://docs.ros.org/en/humble/Concepts/Intermediate/About-Quality-of-Service-Settings.html#qos-compatibilities + * + * Reliability::RELIABLE + * Durability::TRANSIENT_LOCAL + * History::KEEP_LAST, depth: 10u + */ + ROS2QoS get_topic_qos() const { + return DEFAULT_PUBLISHER_QOS; + } + + /* + * @brief enable actor ROS publication + */ + virtual void enable_for_ros(carla::streaming::detail::actor_id_type actor_id=0) { + (void) actor_id; + _actor_name_definition->enabled_for_ros = true; + } + + /* + * @brief disable actor ROS publication + */ + virtual void disable_for_ros(carla::streaming::detail::actor_id_type actor_id=0) { + (void) actor_id; + _actor_name_definition->enabled_for_ros = false; + } + + /* + * @brief is the publisher actually enabled for ROS publication + */ + virtual bool is_enabled_for_ros(carla::streaming::detail::actor_id_type actor_id=0) const { + (void) actor_id; + return _actor_name_definition->enabled_for_ros; + } +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/PublisherBaseSensor.h b/LibCarla/source/carla/ros2/publishers/PublisherBaseSensor.h new file mode 100644 index 00000000000..7b643858fb0 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/PublisherBaseSensor.h @@ -0,0 +1,36 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/PublisherBase.h" +#include "carla/ros2/types/SensorActorDefinition.h" + +namespace carla { +namespace ros2 { + +/** + A Publisher base class for publisher that provide data similiar or equal to sensors. + Extends PublisherBase by specialized sensor get_topic_qos(). +*/ +class PublisherBaseSensor : public PublisherBase { +public: + PublisherBaseSensor(std::shared_ptr actor_name_definition) + : PublisherBase(actor_name_definition) {} + virtual ~PublisherBaseSensor() = default; + + /* + * @brief Override ROS2NameRecord::get_topic_qos() for (pseudo) sensor publishers. + * I.e. deploy the rclcpp::SensorDataQoS. + * + * Reliability::BEST_EFFORT + * Durability::VOLATILE + * History::KEEP_LAST, depth: 5u + */ + ROS2QoS get_topic_qos() const { + return DEFAULT_SENSOR_DATA_QOS; + } +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/PublisherBaseTransform.h b/LibCarla/source/carla/ros2/publishers/PublisherBaseTransform.h new file mode 100644 index 00000000000..f3e36b74fc4 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/PublisherBaseTransform.h @@ -0,0 +1,76 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/PublisherBaseSensor.h" + +#include "carla/ros2/publishers/TransformPublisher.h" +#include "carla/ros2/types/CoordinateSystemTransform.h" +#include "carla/ros2/types/Timestamp.h" +#include "carla/ros2/types/Transform.h" +#include "carla/sensor/s11n/SensorHeaderSerializer.h" + +namespace carla { +namespace ros2 { + +/** + A Publisher base class that is extended to store an internal Transform. + Use this class for publisher that need a transform conversion for the TF tree in addition. + */ +class PublisherBaseTransform : public PublisherBaseSensor { +public: + using CoordinateSystemTransform = carla::ros2::types::CoordinateSystemTransform; + + PublisherBaseTransform(std::shared_ptr actor_name_definition, + std::shared_ptr transform_publisher) + : PublisherBaseSensor(actor_name_definition), _transform_publisher(transform_publisher) {} + virtual ~PublisherBaseTransform() = default; + + /** + * Update the internal transform state with the new transform. + */ + void UpdateTransform(std::shared_ptr sensor_header) { + UpdateTransform(ros2::types::Timestamp(sensor_header->timestamp), + ros2::types::Transform(sensor_header->sensor_relative_transform, + sensor_header->sensor_relative_transform_quaternion)); + } + + /** + * Update the internal transform state with the new transform. + */ + void UpdateTransform(ros2::types::Timestamp const &ros_timestamp, ros2::types::Transform const &ros_transform) { + _timestamp = ros_timestamp; + _transform = ros_transform; + _transform_publisher->AddTransform(_timestamp.time(), frame_id(), parent_frame_id(), _transform.transform()); + } + + /** + * The resulting ROS geometry_msgs::msg::Accel + */ + geometry_msgs::msg::Transform transform() const { + return _transform.transform(); + } + + /** + * The input carla location + */ + carla::geom::Location const &GetLocation() const { + return _transform.GetLocation(); + } + + /** + * The input carla quaternion + */ + carla::geom::Quaternion const &GetQuaternion() const { + return _transform.GetQuaternion(); + } + +protected: + carla::ros2::types::Timestamp _timestamp; + carla::ros2::types::Transform _transform; + std::shared_ptr _transform_publisher; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/PublisherImpl.h b/LibCarla/source/carla/ros2/publishers/PublisherImpl.h deleted file mode 100644 index 87dcd45787b..00000000000 --- a/LibCarla/source/carla/ros2/publishers/PublisherImpl.h +++ /dev/null @@ -1,139 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include - -#include -#include -#include - -#include -#include - -#include -#include -#include -#include - -#include - -#include - -#include -#include - -#include "carla/Logging.h" - -namespace carla { -namespace ros2 { - - namespace efd = eprosima::fastdds::dds; - using erc = eprosima::fastrtps::types::ReturnCode_t; - - template - class PublisherImpl : public eprosima::fastdds::dds::DataWriterListener { - public: - using msg_type = typename T::msg_type; - using msg_pubsub_type = typename T::msg_pubsub_type; - - efd::DomainParticipant* _participant { nullptr }; - efd::Publisher* _publisher { nullptr }; - efd::Topic* _topic { nullptr }; - efd::DataWriter* _datawriter { nullptr }; - efd::TypeSupport _type { new msg_pubsub_type() }; - - void on_publication_matched(efd::DataWriter* writer, const efd::PublicationMatchedStatus& info) override { - _alive = (info.total_count > 0) ? true : false; - } - - ~PublisherImpl() { - if (_datawriter) - _publisher->delete_datawriter(_datawriter); - - if (_publisher) - _participant->delete_publisher(_publisher); - - if (_topic) - _participant->delete_topic(_topic); - - if (_participant) - efd::DomainParticipantFactory::get_instance()->delete_participant(_participant); - } - - bool Init(std::string topic_name) { - if (_type == nullptr) { - log_error("Invalid TypeSupport"); - return false; - } - - efd::DomainParticipantQos pqos = efd::PARTICIPANT_QOS_DEFAULT; - auto factory = efd::DomainParticipantFactory::get_instance(); - _participant = factory->create_participant(0, pqos); - if (_participant == nullptr) { - log_error("Failed to create DomainParticipant"); - return false; - } - _type.register_type(_participant); - - efd::PublisherQos pubqos = efd::PUBLISHER_QOS_DEFAULT; - _publisher = _participant->create_publisher(pubqos, nullptr); - if (_publisher == nullptr) { - log_error("Failed to create Publisher"); - return false; - } - - efd::TopicQos tqos = efd::TOPIC_QOS_DEFAULT; - _topic = _participant->create_topic(topic_name, _type->getName(), tqos); - if (_topic == nullptr) { - log_error("Failed to create Topic"); - return false; - } - - efd::DataWriterQos wqos = efd::DATAWRITER_QOS_DEFAULT; - wqos.endpoint().history_memory_policy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; - efd::DataWriterListener* listener = (efd::DataWriterListener*)(this); - _datawriter = _publisher->create_datawriter(_topic, wqos, listener); - if (_datawriter == nullptr) { - std::cerr << "Failed to create DataWriter" << std::endl; - return false; - } - - _topic_name = topic_name; - return true; - } - - std::string GetTopicName() { - return _topic_name; - } - - bool IsAlive() { - return _alive; - } - - msg_type* GetMessage() { - return &_message; - } - - bool Publish() { - eprosima::fastrtps::rtps::InstanceHandle_t instance_handle; - eprosima::fastrtps::types::ReturnCode_t rcode = _datawriter->write(&_message, instance_handle); - if (rcode == eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_OK) { - return true; - } else { - log_error("PublisherImpl::Publish (", this->GetTopicName(), ") failed with code:", rcode()); - return false; - } - } - - private: - std::string _topic_name; - - bool _alive { false }; - msg_type _message; - }; - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/PublisherInterface.h b/LibCarla/source/carla/ros2/publishers/PublisherInterface.h new file mode 100644 index 00000000000..63a756ca500 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/PublisherInterface.h @@ -0,0 +1,54 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "builtin_interfaces/msg/Time.h" +#include "carla/BufferView.h" +#include "carla/ros2/ROS2NameRecord.h" +#include "carla/ros2/types/Transform.h" +#include "carla/sensor/data/SerializerVectorAllocator.h" + +namespace carla { +namespace ros2 { + +/** + * @brief Generic publisher interface. + * + * This interface is used to hide the implementation part of publishers Publish() function. + * The Publisher inherits this and usually forwards this to the respective publisher impl's it's providing. + */ +class PublisherInterface { +public: + PublisherInterface() = default; + virtual ~PublisherInterface() = default; + /** + * Copy operation not allowed due to active publisher + */ + PublisherInterface(const PublisherInterface&) = delete; + /** + * Assignment operation not allowed due to active publisher + */ + PublisherInterface& operator=(const PublisherInterface&) = delete; + /** + * Move constructor not allowed due to active publisher. + */ + PublisherInterface(PublisherInterface&&) = delete; + /** + * Move assignment operation not allowed due to active publisher. + */ + PublisherInterface& operator=(PublisherInterface&&) = delete; + + /** + * Publish the message + */ + virtual bool Publish() = 0; + + /** + * Should return \c true in case there are subscribers connected to the publisher. + */ + virtual bool SubscribersConnected() const = 0; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/TrafficLightPublisher.cpp b/LibCarla/source/carla/ros2/publishers/TrafficLightPublisher.cpp new file mode 100644 index 00000000000..38a92c83dbe --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/TrafficLightPublisher.cpp @@ -0,0 +1,76 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "TrafficLightPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +TrafficLightPublisher::TrafficLightPublisher( + std::shared_ptr traffic_light_actor_definition, + std::shared_ptr objects_publisher, + std::shared_ptr objects_with_covariance_publisher, + std::shared_ptr traffic_lights_publisher) + : PublisherBaseSensor( + std::static_pointer_cast(traffic_light_actor_definition)), + _traffic_light_info(std::make_shared()), + _traffic_light_status(std::make_shared()), + _traffic_light_object_publisher(std::make_shared(*this, objects_publisher)), + _traffic_light_object_with_covariance_publisher(std::make_shared(*this, objects_with_covariance_publisher)), + _traffic_lights_publisher(traffic_lights_publisher) { + // prefill some traffic_light info data + _traffic_light_info->Message().id(traffic_light_actor_definition->id); + // TODO: add respective data to actor definitions + // _traffic_light_info->Message().trigger_volume(??); +} + +bool TrafficLightPublisher::Init(std::shared_ptr domain_participant) { + return _traffic_light_info->Init(domain_participant, get_topic_name("traffic_light_info"), + PublisherBase::get_topic_qos()) && + _traffic_light_status->Init(domain_participant, get_topic_name("traffic_light_status"), + PublisherBase::get_topic_qos()) && + _traffic_light_object_publisher->Init(domain_participant) && + _traffic_light_object_with_covariance_publisher->Init(domain_participant); +} + +bool TrafficLightPublisher::Publish() { + if (_traffic_light_info_initialized && (!_traffic_light_info_published)) { + _traffic_light_info_published = _traffic_light_info->Publish(); + } + bool success = _traffic_light_info_published; + success &= _traffic_light_status->Publish(); + success &= _traffic_light_object_publisher->Publish(); + success &= _traffic_light_object_with_covariance_publisher->Publish(); + return success; +} + +bool TrafficLightPublisher::SubscribersConnected() const { + return _traffic_light_info->SubscribersConnected() || _traffic_light_status->SubscribersConnected() || + _traffic_light_object_publisher->SubscribersConnected() || _traffic_light_object_with_covariance_publisher->SubscribersConnected(); +} + +void TrafficLightPublisher::UpdateTrafficLight(std::shared_ptr &object, + carla::sensor::data::ActorDynamicState const &actor_dynamic_state) { + if (!_traffic_light_info_initialized) { + _traffic_light_info_initialized = true; + _traffic_light_info->Message().transform(object->Transform().pose()); + _traffic_light_info->SetMessageUpdated(); + _traffic_lights_publisher->UpdateTrafficLightInfo(_traffic_light_info->Message()); + } + + if (_traffic_light_status->Message().state() != carla::ros2::types::GetTrafficLightState(actor_dynamic_state)) { + _traffic_light_status->SetMessageHeader(object->Timestamp().time(), "map"); + _traffic_light_status->Message().id(_traffic_light_info->Message().id()); + _traffic_light_status->Message().state(carla::ros2::types::GetTrafficLightState(actor_dynamic_state)); + } + + _traffic_light_object_publisher->UpdateObject(object); + _traffic_light_object_with_covariance_publisher->UpdateObject(object); + _traffic_lights_publisher->UpdateTrafficLightStatus(_traffic_light_status->Message()); +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/TrafficLightPublisher.h b/LibCarla/source/carla/ros2/publishers/TrafficLightPublisher.h new file mode 100644 index 00000000000..a95d351bdff --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/TrafficLightPublisher.h @@ -0,0 +1,60 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/ObjectPublisher.h" +#include "carla/ros2/publishers/ObjectWithCovariancePublisher.h" +#include "carla/ros2/publishers/PublisherBaseSensor.h" +#include "carla/ros2/publishers/TrafficLightsPublisher.h" +#include "carla/ros2/types/Object.h" +#include "carla/ros2/types/TrafficLightActorDefinition.h" +#include "carla/sensor/data/ActorDynamicState.h" +#include "carla_msgs/msg/CarlaTrafficLightInfoPubSubTypes.h" +#include "carla_msgs/msg/CarlaTrafficLightStatusPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using TrafficLightInfoPublisherImpl = + DdsPublisherImpl; +using TrafficLightStatusPublisherImpl = + DdsPublisherImpl; + +class TrafficLightPublisher : public PublisherBaseSensor { +public: + TrafficLightPublisher(std::shared_ptr traffic_light_actor_definition, + std::shared_ptr objects_publisher, + std::shared_ptr objects_with_covariance_publisher, + std::shared_ptr traffic_lights_publisher); + virtual ~TrafficLightPublisher() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + void UpdateTrafficLight(std::shared_ptr &object, + carla::sensor::data::ActorDynamicState const &actor_dynamic_state); + +private: + std::shared_ptr _traffic_light_info; + bool _traffic_light_info_initialized{false}; + bool _traffic_light_info_published{false}; + std::shared_ptr _traffic_light_status; + std::shared_ptr _traffic_light_object_publisher; + std::shared_ptr _traffic_light_object_with_covariance_publisher; + std::shared_ptr _traffic_lights_publisher; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/TrafficLightsPublisher.cpp b/LibCarla/source/carla/ros2/publishers/TrafficLightsPublisher.cpp new file mode 100644 index 00000000000..8ac7dc4cd81 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/TrafficLightsPublisher.cpp @@ -0,0 +1,73 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "TrafficLightsPublisher.h" + +#include +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +TrafficLightsPublisher::TrafficLightsPublisher() + : PublisherBaseSensor(carla::ros2::types::ActorNameDefinition::CreateFromRoleName("traffic_lights")), + _traffic_light_info(std::make_shared()), + _traffic_light_status(std::make_shared()) {} + +bool TrafficLightsPublisher::Init(std::shared_ptr domain_participant) { + return _traffic_light_info->InitHistoryPreallocatedWithReallocMemoryMode(domain_participant, get_topic_name("info"), + PublisherBase::get_topic_qos()) && + _traffic_light_status->InitHistoryPreallocatedWithReallocMemoryMode( + domain_participant, get_topic_name("status"), PublisherBase::get_topic_qos()); +} + +bool TrafficLightsPublisher::Publish() { + return _traffic_light_info->Publish() && _traffic_light_status->Publish(); +} + +bool TrafficLightsPublisher::SubscribersConnected() const { + return _traffic_light_info->SubscribersConnected() || _traffic_light_status->SubscribersConnected(); +} + +void TrafficLightsPublisher::UpdateTrafficLightStatus( + carla_msgs::msg::CarlaTrafficLightStatus const &traffic_light_status) { + bool traffic_light_found = false; + for (auto &traffic_light : _traffic_light_status->Message().traffic_lights()) { + if (traffic_light.id() == traffic_light_status.id()) { + traffic_light_found = true; + traffic_light = traffic_light_status; + } + } + if (!traffic_light_found) { + _traffic_light_status->Message().traffic_lights().push_back(traffic_light_status); + } + _traffic_light_status->SetMessageUpdated(); +} + +void TrafficLightsPublisher::UpdateTrafficLightInfo(carla_msgs::msg::CarlaTrafficLightInfo const &traffic_light_info) { + bool traffic_light_found = false; + for (auto &traffic_light : _traffic_light_info->Message().traffic_lights()) { + if (traffic_light.id() == traffic_light_info.id()) { + traffic_light_found = true; + traffic_light = traffic_light_info; + } + } + if (!traffic_light_found) { + _traffic_light_info->Message().traffic_lights().push_back(traffic_light_info); + } + _traffic_light_info->SetMessageUpdated(); +} + +void TrafficLightsPublisher::RemoveTrafficLight(carla::streaming::detail::actor_id_type actor) { + (void)std::remove_if( + _traffic_light_status->Message().traffic_lights().begin(), + _traffic_light_status->Message().traffic_lights().end(), + [actor](carla_msgs::msg::CarlaTrafficLightStatus const traffic_light) { return traffic_light.id() == actor; }); + (void)std::remove_if( + _traffic_light_info->Message().traffic_lights().begin(), _traffic_light_info->Message().traffic_lights().end(), + [actor](carla_msgs::msg::CarlaTrafficLightInfo const traffic_light) { return traffic_light.id() == actor; }); +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/TrafficLightsPublisher.h b/LibCarla/source/carla/ros2/publishers/TrafficLightsPublisher.h new file mode 100644 index 00000000000..905c2575e69 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/TrafficLightsPublisher.h @@ -0,0 +1,48 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/PublisherBaseSensor.h" +#include "carla/rpc/ActorId.h" +#include "carla_msgs/msg/CarlaTrafficLightInfoListPubSubTypes.h" +#include "carla_msgs/msg/CarlaTrafficLightStatusListPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using TrafficLightsInfoPublisherImpl = + DdsPublisherImpl; +using TrafficLightsStatusPublisherImpl = DdsPublisherImpl; + +class TrafficLightsPublisher : public PublisherBaseSensor { +public: + TrafficLightsPublisher(); + virtual ~TrafficLightsPublisher() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + void UpdateTrafficLightStatus(carla_msgs::msg::CarlaTrafficLightStatus const &traffic_light_status); + void UpdateTrafficLightInfo(carla_msgs::msg::CarlaTrafficLightInfo const &traffic_light_info); + void RemoveTrafficLight(carla::streaming::detail::actor_id_type id); + +private: + std::shared_ptr _traffic_light_info; + std::shared_ptr _traffic_light_status; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/TrafficSignPublisher.cpp b/LibCarla/source/carla/ros2/publishers/TrafficSignPublisher.cpp new file mode 100644 index 00000000000..37810cbce25 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/TrafficSignPublisher.cpp @@ -0,0 +1,40 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "TrafficSignPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +TrafficSignPublisher::TrafficSignPublisher( + std::shared_ptr traffic_sign_actor_definition, + std::shared_ptr objects_publisher, + std::shared_ptr objects_with_covariance_publisher) + : PublisherBaseSensor( + std::static_pointer_cast(traffic_sign_actor_definition)), + _traffic_sign_object_publisher(std::make_shared(*this, objects_publisher)), + _traffic_sign_object_with_covariance_publisher(std::make_shared(*this, objects_with_covariance_publisher)) {} + +bool TrafficSignPublisher::Init(std::shared_ptr domain_participant) { + return _traffic_sign_object_publisher->Init(domain_participant) && _traffic_sign_object_with_covariance_publisher->Init(domain_participant); +} + +bool TrafficSignPublisher::Publish() { + return _traffic_sign_object_publisher->Publish() && _traffic_sign_object_with_covariance_publisher->Publish(); +} + +bool TrafficSignPublisher::SubscribersConnected() const { + return _traffic_sign_object_publisher->SubscribersConnected() || _traffic_sign_object_with_covariance_publisher->SubscribersConnected(); +} + +void TrafficSignPublisher::UpdateTrafficSign(std::shared_ptr &object, + carla::sensor::data::ActorDynamicState const &) { + _traffic_sign_object_publisher->UpdateObject(object); + _traffic_sign_object_with_covariance_publisher->UpdateObject(object); +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/TrafficSignPublisher.h b/LibCarla/source/carla/ros2/publishers/TrafficSignPublisher.h new file mode 100644 index 00000000000..90475459ea9 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/TrafficSignPublisher.h @@ -0,0 +1,46 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/ObjectPublisher.h" +#include "carla/ros2/publishers/ObjectWithCovariancePublisher.h" +#include "carla/ros2/publishers/PublisherBaseSensor.h" +#include "carla/ros2/types/Object.h" +#include "carla/ros2/types/TrafficSignActorDefinition.h" +#include "carla/sensor/data/ActorDynamicState.h" + +namespace carla { +namespace ros2 { + +class TrafficSignPublisher : public PublisherBaseSensor { +public: + TrafficSignPublisher(std::shared_ptr traffic_sign_actor_definition, + std::shared_ptr objects_publisher, + std::shared_ptr objects_with_covariance_publisher); + virtual ~TrafficSignPublisher() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + void UpdateTrafficSign(std::shared_ptr &object, + carla::sensor::data::ActorDynamicState const &actor_dynamic_state); + +private: + std::shared_ptr _traffic_sign_object_publisher; + std::shared_ptr _traffic_sign_object_with_covariance_publisher; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/TransformPublisher.cpp b/LibCarla/source/carla/ros2/publishers/TransformPublisher.cpp new file mode 100644 index 00000000000..1febc59730e --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/TransformPublisher.cpp @@ -0,0 +1,45 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#define _USE_MATH_DEFINES +#include + +#include "TransformPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +TransformPublisher::TransformPublisher() + : PublisherBase(carla::ros2::types::ActorNameDefinition::CreateFromRoleName("tf")), + _impl(std::make_shared()) {} + +bool TransformPublisher::Init(std::shared_ptr domain_participant) { + return _impl->InitHistoryPreallocatedWithReallocMemoryMode(domain_participant, "rt/tf", get_topic_qos()); +} + +bool TransformPublisher::Publish() { + auto const success = _impl->Publish(); + if (success) { + _impl->Message().transforms().clear(); + } + return success; +} +bool TransformPublisher::SubscribersConnected() const { + return _impl->SubscribersConnected(); +} + +void TransformPublisher::AddTransform(const builtin_interfaces::msg::Time &stamp, std::string name, std::string parent, + geometry_msgs::msg::Transform const &transform) { + geometry_msgs::msg::TransformStamped ts; + ts.header().stamp(stamp); + ts.header().frame_id(parent); + ts.transform(transform); + ts.child_frame_id(name); + _impl->Message().transforms().push_back(ts); + _impl->SetMessageUpdated(); +} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/TransformPublisher.h b/LibCarla/source/carla/ros2/publishers/TransformPublisher.h new file mode 100644 index 00000000000..ad84665a17b --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/TransformPublisher.h @@ -0,0 +1,42 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/PublisherBase.h" + +#include "carla/ros2/types/Transform.h" +#include "tf2_msgs/msg/TFMessagePubSubTypes.h" + +namespace carla { +namespace ros2 { + +using TransformPublisherImpl = DdsPublisherImpl; + +class TransformPublisher : public PublisherBase { +public: + TransformPublisher(); + virtual ~TransformPublisher() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + void AddTransform(const builtin_interfaces::msg::Time &stamp, std::string name, std::string parent, + geometry_msgs::msg::Transform const &transform); + +private: + std::shared_ptr _impl; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeCollisionPublisher.cpp b/LibCarla/source/carla/ros2/publishers/UeCollisionPublisher.cpp new file mode 100644 index 00000000000..b90e1606a40 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeCollisionPublisher.cpp @@ -0,0 +1,42 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "UeCollisionPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" +#include "carla/ros2/types/CoordinateSystemTransform.h" +#include "carla/sensor/s11n/CollisionEventSerializer.h" + +namespace carla { +namespace ros2 { + +UeCollisionPublisher::UeCollisionPublisher( + std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher) + : UePublisherBaseSensor(sensor_actor_definition, transform_publisher), + _impl(std::make_shared()) {} + +bool UeCollisionPublisher::Init(std::shared_ptr domain_participant) { + return _impl->InitHistoryPreallocatedWithReallocMemoryMode(domain_participant, get_topic_name(), get_topic_qos()); +} + +bool UeCollisionPublisher::Publish() { + return _impl->Publish(); +} + +bool UeCollisionPublisher::SubscribersConnected() const { + return _impl->SubscribersConnected(); +} + +void UeCollisionPublisher::UpdateSensorData( + std::shared_ptr sensor_header, + carla::SharedBufferView buffer_view) { + auto collision_event_data = data(buffer_view); + _impl->SetMessageHeader(GetTime(sensor_header), frame_id()); + _impl->Message().other_actor_id(collision_event_data.other_actor.id); + _impl->Message().normal_impulse() = + CoordinateSystemTransform::TransformLinearAxisMsg(collision_event_data.normal_impulse); +} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeCollisionPublisher.h b/LibCarla/source/carla/ros2/publishers/UeCollisionPublisher.h new file mode 100644 index 00000000000..71db61fc0a9 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeCollisionPublisher.h @@ -0,0 +1,52 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/UePublisherBaseSensor.h" +#include "carla/sensor/s11n/CollisionEventSerializer.h" +#include "carla_msgs/msg/CarlaCollisionEventPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using UeCollisionPublisherImpl = + DdsPublisherImpl; + +class UeCollisionPublisher : public UePublisherBaseSensor { +public: + UeCollisionPublisher(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher); + virtual ~UeCollisionPublisher() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + /** + * Implements UePublisherBaseSensor::UpdateSensorData() interface + */ + void UpdateSensorData(std::shared_ptr sensor_header, + carla::SharedBufferView buffer_view) override; + +private: + + carla::sensor::s11n::CollisionEventSerializer::Data data(carla::SharedBufferView buffer_view) { + return MsgPack::UnPack(buffer_view->data(), buffer_view->size()); + } + + std::shared_ptr _impl; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeDVSCameraPublisher.cpp b/LibCarla/source/carla/ros2/publishers/UeDVSCameraPublisher.cpp new file mode 100644 index 00000000000..ba1bd837b72 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeDVSCameraPublisher.cpp @@ -0,0 +1,123 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "UeDVSCameraPublisher.h" + +#include + +#include "carla/ros2/impl/DdsPublisherImpl.h" +#include "carla/sensor/s11n/DVSEventArraySerializer.h" + +namespace carla { +namespace ros2 { + +UeDVSCameraPublisher::UeDVSCameraPublisher( + std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher) + : UePublisherBaseCamera(sensor_actor_definition, transform_publisher), + _point_cloud(std::make_shared()) {} + +bool UeDVSCameraPublisher::Init(std::shared_ptr domain_participant) { + return UePublisherBaseCamera::Init(domain_participant) && + _point_cloud->InitHistoryPreallocatedWithReallocMemoryMode(domain_participant, get_topic_name("point_cloud"), + get_topic_qos()); +} + +bool UeDVSCameraPublisher::Publish() { + return UePublisherBaseCamera::Publish() && _point_cloud->Publish(); +} + +bool UeDVSCameraPublisher::SubscribersConnected() const { + return UePublisherBaseCamera::SubscribersConnected() || _point_cloud->SubscribersConnected(); +} + +void UeDVSCameraPublisher::UpdateSensorData( + std::shared_ptr sensor_header, + carla::SharedBufferView buffer_view) { + // TODO: we have to overwrite the camera basic stuff, because we don't have a buffer of Image type at hand, + // but rather DVSEventArraySerializer + auto header_view = this->header_view(buffer_view); + auto data_vector_view = this->vector_view(buffer_view); + + const sensor_msgs::msg::CameraInfo camera_info(header_view->height, header_view->width, header_view->fov_angle); + auto const stamp = GetTime(sensor_header); + UpdateCameraInfo(stamp, camera_info); + UpdateImageHeader(stamp, camera_info); + + SetImageData(data_vector_view); + SetPointCloudData(data_vector_view); +} + +void UeDVSCameraPublisher::SetImageData(std::vector &data_vector_view) { + std::vector im_data(image_size(), 0u); + for (size_t i = 0; i < data_vector_view.size(); ++i) { + uint32_t index = (data_vector_view[i].y * width() + data_vector_view[i].x) * num_channels() + + (static_cast(data_vector_view[i].pol) * 2u); + im_data[index] = 255u; + } + _image->Message().data(std::move(im_data)); +} + +void UeDVSCameraPublisher::SetPointCloudData(std::vector &data_vector_view) { + _point_cloud->Message().header(_image->Message().header()); + _point_cloud->SetMessageUpdated(); + + sensor_msgs::msg::PointField descriptor1; + descriptor1.name("x"); + descriptor1.offset(offsetof(DVSEvent, x)); + descriptor1.datatype(sensor_msgs::msg::PointField__UINT16); + descriptor1.count(1); + sensor_msgs::msg::PointField descriptor2; + descriptor2.name("y"); + descriptor2.offset(offsetof(DVSEvent, y)); + descriptor2.datatype(sensor_msgs::msg::PointField__UINT16); + descriptor2.count(1); + sensor_msgs::msg::PointField descriptor3; + descriptor3.name("t"); + descriptor3.offset(offsetof(DVSEvent, t)); + descriptor3.datatype( + sensor_msgs::msg::PointField__FLOAT64); // PointField__INT64 is not existing, but would be required here!! + descriptor3.count(1); + sensor_msgs::msg::PointField descriptor4; + descriptor4.name("pol"); + descriptor4.offset(offsetof(DVSEvent, pol)); + descriptor4.datatype(sensor_msgs::msg::PointField__INT8); + descriptor4.count(1); + + +#pragma pack(push, 1) + // definition of the actual data type to be put into the point_cloud (which is different to DVSEvent!!) + struct DVSPointCloudData { + explicit DVSPointCloudData(DVSEvent event) + : x (event.x) + , y (event.y) + , t (event.t) + , pol (event.pol) + {} + std::uint16_t x; + std::uint16_t y; + double t; + std::int8_t pol; + }; +#pragma pack(pop) + + DEBUG_ASSERT_EQ(num_channels(), 4); + const uint32_t point_size = sizeof(DVSPointCloudData); + _point_cloud->Message().width(width()); + _point_cloud->Message().height(height()); + _point_cloud->Message().is_bigendian(false); + _point_cloud->Message().fields({descriptor1, descriptor2, descriptor3, descriptor4}); + _point_cloud->Message().point_step(point_size); + _point_cloud->Message().row_step(width() * point_size); + _point_cloud->Message().is_dense(false); + std::vector pcl_data_uint8_t; + pcl_data_uint8_t.resize(data_vector_view.size()*point_size); + for (size_t i = 0; i < data_vector_view.size(); ++i) { + // convert the DVSEvent format to DVSPointCloudData putting it directly into the desired array to be sent out + *(reinterpret_cast(pcl_data_uint8_t.data()+i*point_size)) = DVSPointCloudData(data_vector_view[i]); + } + _point_cloud->Message().data(std::move(pcl_data_uint8_t)); +} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeDVSCameraPublisher.h b/LibCarla/source/carla/ros2/publishers/UeDVSCameraPublisher.h new file mode 100644 index 00000000000..54b9137451b --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeDVSCameraPublisher.h @@ -0,0 +1,71 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/UePublisherBaseCamera.h" +#include "carla/sensor/s11n/DVSEventArraySerializer.h" +#include "sensor_msgs/msg/PointCloud2PubSubTypes.h" + +namespace carla { +namespace ros2 { + +using UePointCloudFromBufferPublisherImpl = + DdsPublisherImpl; + +class UeDVSCameraPublisher : public UePublisherBaseCamera { +public: + UeDVSCameraPublisher(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher); + virtual ~UeDVSCameraPublisher() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + /** + * Implements UePublisherBaseSensor::UpdateSensorData() interface + */ + void UpdateSensorData(std::shared_ptr sensor_header, + const carla::SharedBufferView buffer_view) override; + +protected: + /** + * Overrides UePublisherBaseCamera::encoding() + */ + Encoding encoding() const override { + return Encoding::BGR8; + } + +private: + using DVSEvent = carla::sensor::data::DVSEvent; + using DVSHeaderConst = carla::sensor::s11n::DVSEventArraySerializer::DVSHeader const; + using DVSEventVectorAllocator = carla::sensor::data::SerializerVectorAllocator; + + std::shared_ptr header_view(const carla::SharedBufferView buffer_view) { + return std::shared_ptr(buffer_view, reinterpret_cast(buffer_view.get()->data())); + } + + std::vector vector_view(const carla::SharedBufferView buffer_view) { + return carla::sensor::data::buffer_data_accessed_by_vector( + buffer_view, carla::sensor::s11n::DVSEventArraySerializer::header_offset); + } + + void SetImageData(std::vector &data_vector_view); + void SetPointCloudData(std::vector &data_vector_view); + + std::shared_ptr _point_cloud; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeDepthCameraPublisher.cpp b/LibCarla/source/carla/ros2/publishers/UeDepthCameraPublisher.cpp new file mode 100644 index 00000000000..1a89bfdd725 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeDepthCameraPublisher.cpp @@ -0,0 +1,17 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "UeDepthCameraPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +UeDepthCameraPublisher::UeDepthCameraPublisher( + std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher) + : UePublisherBaseCamera(sensor_actor_definition, transform_publisher) {} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeDepthCameraPublisher.h b/LibCarla/source/carla/ros2/publishers/UeDepthCameraPublisher.h new file mode 100644 index 00000000000..c88e6a0a625 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeDepthCameraPublisher.h @@ -0,0 +1,21 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/UePublisherBaseCamera.h" +#include "sensor_msgs/msg/CameraInfoPubSubTypes.h" +#include "sensor_msgs/msg/ImagePubSubTypes.h" + +namespace carla { +namespace ros2 { + +class UeDepthCameraPublisher : public UePublisherBaseCamera { +public: + UeDepthCameraPublisher(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher); + virtual ~UeDepthCameraPublisher() = default; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeGNSSPublisher.cpp b/LibCarla/source/carla/ros2/publishers/UeGNSSPublisher.cpp new file mode 100644 index 00000000000..9c1966904c2 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeGNSSPublisher.cpp @@ -0,0 +1,39 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "UeGNSSPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +UeGNSSPublisher::UeGNSSPublisher(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher) + : UePublisherBaseSensor(sensor_actor_definition, transform_publisher), + _impl(std::make_shared()) {} + +bool UeGNSSPublisher::Init(std::shared_ptr domain_participant) { + return _impl->InitHistoryPreallocatedWithReallocMemoryMode(domain_participant, get_topic_name(), get_topic_qos()); +} + +bool UeGNSSPublisher::Publish() { + return _impl->Publish(); +} +bool UeGNSSPublisher::SubscribersConnected() const { + return _impl->SubscribersConnected(); +} + +void UeGNSSPublisher::UpdateSensorData( + std::shared_ptr sensor_header, + carla::SharedBufferView buffer_view) { + auto gnss_data = data(buffer_view); + + _impl->SetMessageHeader(GetTime(sensor_header), frame_id()); + _impl->Message().latitude(gnss_data.latitude); + _impl->Message().longitude(gnss_data.longitude); + _impl->Message().altitude(gnss_data.altitude); +} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeGNSSPublisher.h b/LibCarla/source/carla/ros2/publishers/UeGNSSPublisher.h new file mode 100644 index 00000000000..fb0b612cc6b --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeGNSSPublisher.h @@ -0,0 +1,53 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include + +#include "carla/ros2/publishers/UePublisherBaseSensor.h" +#include "carla/sensor/s11n/GnssSerializer.h" +#include "sensor_msgs/msg/NavSatFixPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using UeGNSSPublisherImpl = DdsPublisherImpl; + +class UeGNSSPublisher : public UePublisherBaseSensor { +public: + UeGNSSPublisher(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher); + virtual ~UeGNSSPublisher() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + /** + * Implements UePublisherBaseSensor::UpdateSensorData() interface + */ + void UpdateSensorData(std::shared_ptr sensor_header, + const carla::SharedBufferView buffer_view) override; + +private: + + carla::geom::GeoLocation data(carla::SharedBufferView buffer_view) { + return MsgPack::UnPack(buffer_view->data(), buffer_view->size()); + } + + std::shared_ptr _impl; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeIMUPublisher.cpp b/LibCarla/source/carla/ros2/publishers/UeIMUPublisher.cpp new file mode 100644 index 00000000000..ebeae2d9e7c --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeIMUPublisher.cpp @@ -0,0 +1,67 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#define _USE_MATH_DEFINES +#include + +#include "UeIMUPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" +#include "carla/ros2/types/Acceleration.h" +#include "carla/ros2/types/AngularVelocity.h" + +namespace carla { +namespace ros2 { + +UeIMUPublisher::UeIMUPublisher(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher) + : UePublisherBaseSensor(sensor_actor_definition, transform_publisher), + _impl(std::make_shared()) {} + +bool UeIMUPublisher::Init(std::shared_ptr domain_participant) { + return _impl->InitHistoryPreallocatedWithReallocMemoryMode(domain_participant, get_topic_name(), get_topic_qos()); +} + +bool UeIMUPublisher::Publish() { + return _impl->Publish(); +} +bool UeIMUPublisher::SubscribersConnected() const { + return _impl->SubscribersConnected(); +} + +void UeIMUPublisher::UpdateSensorData( + std::shared_ptr sensor_header, + carla::SharedBufferView buffer_view) { + auto imu_data = data(buffer_view); + _impl->SetMessageHeader(GetTime(sensor_header), frame_id()); + _impl->Message().angular_velocity(carla::ros2::types::AngularVelocity(imu_data.gyroscope).angular_velocity()); + _impl->Message().linear_acceleration(carla::ros2::types::Acceleration(imu_data.accelerometer).accel().linear()); + + /* + TODO: original ROS bridge had taken the transform to provide a correct 3D orientation + The question is how this should be implemented by the IMU accoringly + Regardless, the transform of the IMU sensor can still be used within ROS in case the quaternion resulting in the 1D + compass value is not sufficient + */ + + // optimized rotation calculation + /*const float rp = 0.0f; // pitch*/ + const float ry = float(M_PI_2) - imu_data.compass; // -yaw + /*const float rr = 0.0f; // roll*/ + + const float cr = 1.f; + const float sr = 0.f; + const float cp = 1.f; + ; + const float sp = 0.f; + const float cy = cosf(ry * 0.5f); + const float sy = sinf(ry * 0.5f); + + _impl->Message().orientation().w(cr * cp * cy + sr * sp * sy); + _impl->Message().orientation().x(sr * cp * cy - cr * sp * sy); + _impl->Message().orientation().y(cr * sp * cy + sr * cp * sy); + _impl->Message().orientation().z(cr * cp * sy - sr * sp * cy); +} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeIMUPublisher.h b/LibCarla/source/carla/ros2/publishers/UeIMUPublisher.h new file mode 100644 index 00000000000..8180f342b9e --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeIMUPublisher.h @@ -0,0 +1,51 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/UePublisherBaseSensor.h" +#include "carla/sensor/s11n/IMUSerializer.h" +#include "geometry_msgs/msg/Accel.h" +#include "sensor_msgs/msg/ImuPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using UeIMUPublisherImpl = DdsPublisherImpl; + +class UeIMUPublisher : public UePublisherBaseSensor { +public: + UeIMUPublisher(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher); + virtual ~UeIMUPublisher() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + /** + * Implements UePublisherBaseSensor::UpdateSensorData() interface + */ + void UpdateSensorData(std::shared_ptr sensor_header, + const carla::SharedBufferView buffer_view) override; + +private: + carla::sensor::s11n::IMUSerializer::Data data(carla::SharedBufferView buffer_view) { + return MsgPack::UnPack(buffer_view->data(), buffer_view->size()); + } + + std::shared_ptr _impl; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeISCameraPublisher.cpp b/LibCarla/source/carla/ros2/publishers/UeISCameraPublisher.cpp new file mode 100644 index 00000000000..8450d06fe0a --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeISCameraPublisher.cpp @@ -0,0 +1,17 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "UeISCameraPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +UeISCameraPublisher::UeISCameraPublisher( + std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher) + : UePublisherBaseCamera(sensor_actor_definition, transform_publisher) {} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeISCameraPublisher.h b/LibCarla/source/carla/ros2/publishers/UeISCameraPublisher.h new file mode 100644 index 00000000000..f1fb62edba7 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeISCameraPublisher.h @@ -0,0 +1,22 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +#include "carla/ros2/publishers/UePublisherBaseCamera.h" + +namespace carla { +namespace ros2 { + +class UeISCameraPublisher : public UePublisherBaseCamera { +public: + UeISCameraPublisher(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher); + virtual ~UeISCameraPublisher() = default; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeLidarPublisher.cpp b/LibCarla/source/carla/ros2/publishers/UeLidarPublisher.cpp new file mode 100644 index 00000000000..fe0f7b38d58 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeLidarPublisher.cpp @@ -0,0 +1,56 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "UeLidarPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +UeLidarPublisher::UeLidarPublisher(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher) + : UePublisherBasePointCloud(sensor_actor_definition, transform_publisher) {} + +std::vector UeLidarPublisher::GetPointFields() const { + sensor_msgs::msg::PointField descriptor1; + descriptor1.name("x"); + descriptor1.offset(0); + descriptor1.datatype(sensor_msgs::msg::PointField__FLOAT32); + descriptor1.count(1); + sensor_msgs::msg::PointField descriptor2; + descriptor2.name("y"); + descriptor2.offset(4); + descriptor2.datatype(sensor_msgs::msg::PointField__FLOAT32); + descriptor2.count(1); + sensor_msgs::msg::PointField descriptor3; + descriptor3.name("z"); + descriptor3.offset(8); + descriptor3.datatype(sensor_msgs::msg::PointField__FLOAT32); + descriptor3.count(1); + sensor_msgs::msg::PointField descriptor4; + descriptor4.name("intensity"); + descriptor4.offset(12); + descriptor4.datatype(sensor_msgs::msg::PointField__FLOAT32); + descriptor4.count(1); + + return {descriptor1, descriptor2, descriptor3, descriptor4}; +} + +void UeLidarPublisher::SetPointCloudDataFromBuffer(std::shared_ptr header_view, + std::vector data_vector_view) { + DEBUG_ASSERT_EQ(header_view->GetChannelCount(), 4); + DEBUG_ASSERT_EQ(sizeof(LidarDetection), 4 * sizeof(float)); + + _point_cloud->Message().data().resize(data_vector_view.size() * sizeof(LidarDetection) / sizeof(uint8_t)); + auto point_clound_data_iter = reinterpret_cast(_point_cloud->Message().data().data()); + for (auto const &data_view : data_vector_view) { + LidarDetection ros_data(CoordinateSystemTransform::TransformLinearAxixVector3D(data_view.point), + data_view.intensity); + *point_clound_data_iter = ros_data; + ++point_clound_data_iter; + } +} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeLidarPublisher.h b/LibCarla/source/carla/ros2/publishers/UeLidarPublisher.h new file mode 100644 index 00000000000..eaed6a752ce --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeLidarPublisher.h @@ -0,0 +1,29 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/UePublisherBasePointCloud.h" +#include "carla/sensor/s11n/LidarSerializer.h" + +namespace carla { +namespace ros2 { + +class UeLidarPublisher + : public UePublisherBasePointCloud { +public: + UeLidarPublisher(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher); + virtual ~UeLidarPublisher() = default; + +protected: + using LidarDetection = DataType; + + std::vector GetPointFields() const override; + + void SetPointCloudDataFromBuffer(std::shared_ptr header_view, + std::vector vector_view) override; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeNormalsCameraPublisher.cpp b/LibCarla/source/carla/ros2/publishers/UeNormalsCameraPublisher.cpp new file mode 100644 index 00000000000..981d4893c21 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeNormalsCameraPublisher.cpp @@ -0,0 +1,17 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "UeNormalsCameraPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +UeNormalsCameraPublisher::UeNormalsCameraPublisher( + std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher) + : UePublisherBaseCamera(sensor_actor_definition, transform_publisher) {} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeNormalsCameraPublisher.h b/LibCarla/source/carla/ros2/publishers/UeNormalsCameraPublisher.h new file mode 100644 index 00000000000..ffa774bf3f9 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeNormalsCameraPublisher.h @@ -0,0 +1,24 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +#include "carla/ros2/publishers/UePublisherBaseCamera.h" +#include "sensor_msgs/msg/CameraInfoPubSubTypes.h" +#include "sensor_msgs/msg/ImagePubSubTypes.h" + +namespace carla { +namespace ros2 { + +class UeNormalsCameraPublisher : public UePublisherBaseCamera { +public: + UeNormalsCameraPublisher(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher); + virtual ~UeNormalsCameraPublisher() = default; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeOpticalFlowCameraPublisher.cpp b/LibCarla/source/carla/ros2/publishers/UeOpticalFlowCameraPublisher.cpp new file mode 100644 index 00000000000..531a0476f74 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeOpticalFlowCameraPublisher.cpp @@ -0,0 +1,110 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "UeOpticalFlowCameraPublisher.h" + +#include + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +template +T CLAMP(const T& value, const T& low, const T& high) { + return value < low ? low : (value > high ? high : value); +} + +namespace carla { +namespace ros2 { + +UeOpticalFlowCameraPublisher::UeOpticalFlowCameraPublisher( + std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher) + : UePublisherBaseCamera(sensor_actor_definition, transform_publisher) {} + +void UeOpticalFlowCameraPublisher::SetImageDataFromBuffer(const carla::SharedBufferView buffer_view) { + constexpr float pi = 3.1415f; + constexpr float rad2ang = 360.0f / (2.0f * pi); + auto data = carla::sensor::data::buffer_data_accessed_by_vector( + buffer_view, carla::sensor::s11n::ImageSerializer::header_offset); + + std::vector image_data(image_size()); + size_t data_index = 0; + for (size_t index = 0; index < data.size() && data_index < image_data.size() - 4; index += 2) { + const float vx = data[index]; + const float vy = data[index + 1]; + float angle = 180.0f + std::atan2(vy, vx) * rad2ang; + if (angle < 0) { + angle = 360.0f + angle; + } + angle = std::fmod(angle, 360.0f); + + const float norm = std::sqrt(vx * vx + vy * vy); + const float shift = 0.999f; + const float a = 1.0f / std::log(0.1f + shift); + const float intensity = CLAMP(a * std::log(norm + shift), 0.0f, 1.0f); + + const float& H = angle; + const float S = 1.0f; + const float V = intensity; + const float H_60 = H * (1.0f / 60.0f); + + const float C = V * S; + const float X = C * (1.0f - std::abs(std::fmod(H_60, 2.0f) - 1.0f)); + const float m = V - C; + + float r = 0; + float g = 0; + float b = 0; + const unsigned int angle_case = static_cast(H_60); + switch (angle_case) { + case 0: + r = C; + g = X; + b = 0; + break; + case 1: + r = X; + g = C; + b = 0; + break; + case 2: + r = 0; + g = C; + b = X; + break; + case 3: + r = 0; + g = X; + b = C; + break; + case 4: + r = X; + g = 0; + b = C; + break; + case 5: + r = C; + g = 0; + b = X; + break; + default: + r = 1; + g = 1; + b = 1; + break; + } + + const uint8_t R = static_cast((r + m) * 255.0f); + const uint8_t G = static_cast((g + m) * 255.0f); + const uint8_t B = static_cast((b + m) * 255.0f); + + image_data[data_index++] = B; + image_data[data_index++] = G; + image_data[data_index++] = R; + image_data[data_index++] = 0; + } + DEBUG_ASSERT_EQ(data_index, image_data.size()); + _image->Message().data(std::move(image_data)); +} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeOpticalFlowCameraPublisher.h b/LibCarla/source/carla/ros2/publishers/UeOpticalFlowCameraPublisher.h new file mode 100644 index 00000000000..05023fa5b3a --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeOpticalFlowCameraPublisher.h @@ -0,0 +1,25 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/UePublisherBaseCamera.h" + +namespace carla { +namespace ros2 { + +class UeOpticalFlowCameraPublisher : public UePublisherBaseCamera { +public: + UeOpticalFlowCameraPublisher(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher); + virtual ~UeOpticalFlowCameraPublisher() = default; + +protected: + /** + * Overrides UePublisherBaseCamera::SetImageDataFromBuffer() + */ + void SetImageDataFromBuffer(const carla::SharedBufferView buffer_view) override; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UePublisherBaseCamera.cc b/LibCarla/source/carla/ros2/publishers/UePublisherBaseCamera.cc new file mode 100644 index 00000000000..306eef14140 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UePublisherBaseCamera.cc @@ -0,0 +1,96 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/ros2/publishers/UePublisherBaseCamera.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" +#include "carla/sensor/s11n/ImageSerializer.h" + +namespace carla { +namespace ros2 { + +template +UePublisherBaseCamera::UePublisherBaseCamera( + std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher) + : UePublisherBaseSensor(sensor_actor_definition, transform_publisher), + _image(std::make_shared >()), + _camera_info(std::make_shared()) {} + +template +bool UePublisherBaseCamera::Init(std::shared_ptr domain_participant) { + return _image->InitHistoryPreallocatedWithReallocMemoryMode(domain_participant, get_topic_name("image"), + get_topic_qos()) && + // camera info uses standard publisher qos + _camera_info->Init(domain_participant, get_topic_name("camera_info"), PublisherBase::get_topic_qos()); +} + +template +bool UePublisherBaseCamera::Publish() { + return _camera_info_initialized && _image->Publish() && _camera_info->Publish(); +} + +template +bool UePublisherBaseCamera::SubscribersConnected() const { + return _image->SubscribersConnected() || _camera_info->SubscribersConnected(); +} + +template +void UePublisherBaseCamera::UpdateCameraInfo(const builtin_interfaces::msg::Time &stamp, + sensor_msgs::msg::CameraInfo const &camera_info) { + _camera_info->SetMessageHeader(stamp, frame_id()); + _camera_info->Message() = camera_info; + _camera_info->Message().roi().x_offset(0); // up-to-data: constantly 0 + _camera_info->Message().roi().y_offset(0); // up-to-data: constantly 0 + _camera_info->Message().roi().height(camera_info.height()); + _camera_info->Message().roi().width(camera_info.width()); + _camera_info->Message().roi().do_rectify(true); // up-to-data: constantly true + _camera_info_initialized = true; +} + +template +void UePublisherBaseCamera::UpdateImageHeader(const builtin_interfaces::msg::Time &stamp, + sensor_msgs::msg::CameraInfo const &camera_info) { + // Handle image data + _image->SetMessageHeader(stamp, frame_id()); + _image->Message().width(camera_info.width()); + _image->Message().height(camera_info.height()); + _image->Message().encoding(encoding_as_string()); + _image->Message().is_bigendian(0); + _image->Message().step(line_stride()); +} + +template +void UePublisherBaseCamera::UpdateSensorData( + std::shared_ptr sensor_header, + carla::SharedBufferView buffer_view) { + auto header_view = UePublisherBaseCamera::header_view(buffer_view); + if (!header_view) { + return; + } + + const sensor_msgs::msg::CameraInfo camera_info(header_view->height, header_view->width, header_view->fov_angle); + auto const stamp = GetTime(sensor_header); + UpdateCameraInfo(stamp, camera_info); + UpdateImageHeader(stamp, _camera_info->Message()); + + SetImageDataFromBuffer(buffer_view); +} + +template +void UePublisherBaseCamera::SetImageDataFromBuffer(const carla::SharedBufferView buffer_view) { + _image->Message().data(buffer_data_2_vector(buffer_view)); +} + +template +uint32_t UePublisherBaseCamera::width() const { + return _image->Message().width(); +} + +template +uint32_t UePublisherBaseCamera::height() const { + return _image->Message().height(); +} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UePublisherBaseCamera.h b/LibCarla/source/carla/ros2/publishers/UePublisherBaseCamera.h new file mode 100644 index 00000000000..3a7ba02d01c --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UePublisherBaseCamera.h @@ -0,0 +1,210 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/Exception.h" +#include "carla/ros2/publishers/UePublisherBaseSensor.h" +#include "carla/sensor/s11n/ImageSerializer.h" +#include "sensor_msgs/msg/CameraInfoPubSubTypes.h" +#include "sensor_msgs/msg/ImagePubSubTypes.h" + +namespace carla { +namespace ros2 { + +template +using UeImagePublisherImpl = + DdsPublisherImpl, sensor_msgs::msg::ImagePubSubTypeT>; +using UeCameraInfoPublisherImpl = + DdsPublisherImpl; + +/** +A Publisher base class for camera sensors. +Extends UePublisherBaseSensor by an image and camera_info publisher providing default implemenations for sending the +camera data from the rendering buffer copyless via DDS +*/ +template +class UePublisherBaseCamera : public UePublisherBaseSensor { +public: + using allocator_type = ALLOCATOR; + + UePublisherBaseCamera(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher); + virtual ~UePublisherBaseCamera() = default; + + /** + * Some Encodings from + * https://github.com/ros/common_msgs/blob/846bfcb/sensor_msgs/include/sensor_msgs/image_encodings.h Extend this list + * (and the corresponding implementations of to_string(), num_channels(), bit_depth() + */ + enum class Encoding { RGB8, RGBA8, RGB16, RGBA16, BGR8, BGRA8, BGR16, BGRA16, MONO8, MONO16 }; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + /** + * Implements UePublisherBaseSensor::UpdateSensorData() interface + */ + void UpdateSensorData(std::shared_ptr sensor_header, + const carla::SharedBufferView buffer_view) override; + +protected: + void UpdateCameraInfo(const builtin_interfaces::msg::Time &stamp, sensor_msgs::msg::CameraInfo const &camera_info); + void UpdateImageHeader(const builtin_interfaces::msg::Time &stamp, sensor_msgs::msg::CameraInfo const &camera_info); + + virtual void SetImageDataFromBuffer(const carla::SharedBufferView buffer_view); + + /** + * encoding of the stream, defaults to Encoding::BGRA8 + */ + virtual Encoding encoding() const { + return Encoding::BGRA8; + } + + using ImageHeaderConst = carla::sensor::s11n::ImageSerializer::ImageHeader const; + + /** + * @brief provides access to the image header stored at the start of the buffer + */ + std::shared_ptr header_view(const carla::SharedBufferView buffer_view) { + return std::shared_ptr(buffer_view, + reinterpret_cast(buffer_view.get()->data())); + } + + /** + * @brief calculates the number of elements of the buffer view by reducing the buffer size by the + * carla::sensor::s11n::ImageSerializer::header_offset and division by sizeof(T) + */ + template + std::size_t number_of_elements(const carla::SharedBufferView buffer_view) const { + return carla::sensor::data::number_of_elements(buffer_view, carla::sensor::s11n::ImageSerializer::header_offset); + } + + /** + * @brief the vector creation method matching the ALLOCATOR type of this class + * + * This function is called for sensor_msgs::msg::Image types + */ + template ::value, bool> = true > + std::vector buffer_data_2_vector(const carla::SharedBufferView buffer_view) const { + return carla::sensor::data::buffer_data_copy_to_std_vector(buffer_view, + carla::sensor::s11n::ImageSerializer::header_offset); + } + + /** + * @brief the vector creation method matching the ALLOCATOR type of this class + * + * This function is called for sensor_msgs::msg::ImageFromBuffer types + */ + template ::value, bool> = true > + std::vector> buffer_data_2_vector( + const carla::SharedBufferView buffer_view) const { + return carla::sensor::data::buffer_data_accessed_by_vector(buffer_view, + carla::sensor::s11n::ImageSerializer::header_offset); + } + + std::string encoding_as_string() const { + switch (encoding()) { + case UePublisherBaseCamera::Encoding::RGB8: + return "rgb8"; + case UePublisherBaseCamera::Encoding::RGBA8: + return "rgba8"; + case UePublisherBaseCamera::Encoding::RGB16: + return "rgb16"; + case UePublisherBaseCamera::Encoding::RGBA16: + return "rgba16"; + case UePublisherBaseCamera::Encoding::BGR8: + return "bgr8"; + case UePublisherBaseCamera::Encoding::BGRA8: + return "bgra8"; + case UePublisherBaseCamera::Encoding::BGR16: + return "bgr16"; + case UePublisherBaseCamera::Encoding::BGRA16: + return "bgra16"; + case UePublisherBaseCamera::Encoding::MONO8: + return "mono8"; + case UePublisherBaseCamera::Encoding::MONO16: + return "mono16"; + default: + carla::throw_exception(std::invalid_argument("UePublisherBaseCamera::to_string encoding " + + std::to_string(int(encoding())) + " not found")); + } + } + + uint32_t num_channels() const { + switch (encoding()) { + case UePublisherBaseCamera::Encoding::MONO8: + case UePublisherBaseCamera::Encoding::MONO16: + return 1u; + case UePublisherBaseCamera::Encoding::RGB8: + case UePublisherBaseCamera::Encoding::BGR8: + case UePublisherBaseCamera::Encoding::RGB16: + case UePublisherBaseCamera::Encoding::BGR16: + return 3u; + case UePublisherBaseCamera::Encoding::RGBA8: + case UePublisherBaseCamera::Encoding::BGRA8: + case UePublisherBaseCamera::Encoding::RGBA16: + case UePublisherBaseCamera::Encoding::BGRA16: + return 4u; + default: + carla::throw_exception(std::invalid_argument("UePublisherBaseCamera::pixel_size_in_byte encoding " + + std::to_string(int(encoding())) + " not found")); + } + } + + uint32_t bit_depth() const { + switch (encoding()) { + case UePublisherBaseCamera::Encoding::RGB8: + case UePublisherBaseCamera::Encoding::RGBA8: + case UePublisherBaseCamera::Encoding::BGR8: + case UePublisherBaseCamera::Encoding::BGRA8: + case UePublisherBaseCamera::Encoding::MONO8: + return 1u; + case UePublisherBaseCamera::Encoding::RGB16: + case UePublisherBaseCamera::Encoding::RGBA16: + case UePublisherBaseCamera::Encoding::BGR16: + case UePublisherBaseCamera::Encoding::BGRA16: + case UePublisherBaseCamera::Encoding::MONO16: + return 2u; + default: + carla::throw_exception(std::invalid_argument("UePublisherBaseCamera::pixel_size_in_byte encoding " + + std::to_string(int(encoding())) + " not found")); + } + } + + uint32_t pixel_stride() const { + return bit_depth() * num_channels(); + } + + uint32_t line_stride() const { + return bit_depth() * num_channels() * width(); + } + + uint32_t image_size() const { + return line_stride() * height(); + } + uint32_t width() const; + uint32_t height() const; + + std::shared_ptr> _image; + std::shared_ptr _camera_info; + bool _camera_info_initialized{false}; +}; +} // namespace ros2 +} // namespace carla + +#include "UePublisherBaseCamera.cc" diff --git a/LibCarla/source/carla/ros2/publishers/UePublisherBasePointCloud.cc b/LibCarla/source/carla/ros2/publishers/UePublisherBasePointCloud.cc new file mode 100644 index 00000000000..af1a3bdf5f0 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UePublisherBasePointCloud.cc @@ -0,0 +1,55 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/ros2/publishers/UePublisherBasePointCloud.h" +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +template +UePublisherBasePointCloud::UePublisherBasePointCloud( + std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher) + : UePublisherBaseSensor(sensor_actor_definition, transform_publisher), + _point_cloud(std::make_shared()) {} + +template +bool UePublisherBasePointCloud::Init( + std::shared_ptr domain_participant) { + return _point_cloud->InitHistoryPreallocatedWithReallocMemoryMode(domain_participant, get_topic_name(), + get_topic_qos()); +} + +template +bool UePublisherBasePointCloud::Publish() { + return _point_cloud->Publish(); +} + +template +bool UePublisherBasePointCloud::SubscribersConnected() const { + return _point_cloud->SubscribersConnected(); +} + +template +void UePublisherBasePointCloud::UpdateSensorData( + std::shared_ptr sensor_header, + carla::SharedBufferView buffer_view) { + auto header_view = this->header_view(buffer_view); + auto data_vector_view = this->vector_view(buffer_view); + + _point_cloud->SetMessageHeader(GetTime(sensor_header), frame_id()); + const size_t point_size = GetMessagePointSize(); + _point_cloud->Message().width(1); + _point_cloud->Message().height(uint32_t(data_vector_view.size())); + _point_cloud->Message().is_bigendian(false); + _point_cloud->Message().fields(GetPointFields()); + _point_cloud->Message().point_step(point_size); + _point_cloud->Message().row_step(_point_cloud->Message().width() * point_size); + _point_cloud->Message().is_dense(false); // True if there are not invalid points + + SetPointCloudDataFromBuffer(header_view, data_vector_view); +} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UePublisherBasePointCloud.h b/LibCarla/source/carla/ros2/publishers/UePublisherBasePointCloud.h new file mode 100644 index 00000000000..afd1b52cd21 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UePublisherBasePointCloud.h @@ -0,0 +1,74 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/UePublisherBaseSensor.h" +#include "sensor_msgs/msg/PointCloud2PubSubTypes.h" + +namespace carla { +namespace ros2 { + +using UePublisherPointCloudImpl = + DdsPublisherImpl; + +/** + A Publisher base class for point cloud publisher sensors. + Extends UePublisherBaseSensor by an point cloud publisher. +*/ +template +class UePublisherBasePointCloud : public UePublisherBaseSensor { +public: + UePublisherBasePointCloud(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher); + virtual ~UePublisherBasePointCloud() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + /** + * Implements UePublisherBaseSensor::UpdateSensorData() interface + */ + void UpdateSensorData(std::shared_ptr sensor_header, + const carla::SharedBufferView buffer_view) override; + +protected: + using DataType = DATA_TYPE; + using HeaderTypeConst = HEADER_TYPE const; + using DataVectorAllocator = carla::sensor::data::SerializerVectorAllocator; + + std::shared_ptr header_view(const carla::SharedBufferView buffer_view) const { + return std::shared_ptr( + buffer_view, new HeaderTypeConst(reinterpret_cast(buffer_view.get()->data()))); + } + + std::vector vector_view(const carla::SharedBufferView buffer_view) const { + auto header_view = UePublisherBasePointCloud::header_view(buffer_view); + auto const header_offset = header_view->GetHeaderOffset(); + return carla::sensor::data::buffer_data_accessed_by_vector(buffer_view, header_offset); + } + + virtual std::vector GetPointFields() const = 0; + virtual size_t GetMessagePointSize() const { return sizeof(DataType); } + + virtual void SetPointCloudDataFromBuffer(std::shared_ptr header_view, + std::vector vector_view) = 0; + + std::shared_ptr _point_cloud; +}; +} // namespace ros2 +} // namespace carla + +#include "UePublisherBasePointCloud.cc" \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/publishers/UePublisherBaseSensor.h b/LibCarla/source/carla/ros2/publishers/UePublisherBaseSensor.h new file mode 100644 index 00000000000..46afe2b265f --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UePublisherBaseSensor.h @@ -0,0 +1,49 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/PublisherBaseTransform.h" +#include "carla/rpc/ActorId.h" + +namespace carla { +namespace ros2 { + +/** + A Publisher base class for sensors receiving their data directly from UE4 via buffers. + Extends PublisherBaseTransform by UpdateSensorData() function. + */ +class UePublisherBaseSensor : public PublisherBaseTransform { +public: + UePublisherBaseSensor(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher) + : PublisherBaseTransform(sensor_actor_definition, transform_publisher) {} + virtual ~UePublisherBaseSensor() = default; + + /** + * Implement actions before sensor data updates + */ + virtual void UpdateSensorDataPreAction() {}; + /** + * Function to update the data for this sensor + */ + virtual void UpdateSensorData( + std::shared_ptr sensor_header, + carla::SharedBufferView buffer_view) = 0; + /** + * Implement actions after sensor data updates + */ + virtual void UpdateSensorDataPostAction() {}; + + builtin_interfaces::msg::Time GetTime( + std::shared_ptr sensor_header) const { + return carla::ros2::types::Timestamp(sensor_header->timestamp).time(); + } + + std::shared_ptr GetSensorActorDefinition() const { + return std::static_pointer_cast(_actor_name_definition); + } +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeRGBCameraPublisher.cpp b/LibCarla/source/carla/ros2/publishers/UeRGBCameraPublisher.cpp new file mode 100644 index 00000000000..0699abd9a9a --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeRGBCameraPublisher.cpp @@ -0,0 +1,17 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "UeRGBCameraPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +UeRGBCameraPublisher::UeRGBCameraPublisher( + std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher) + : UePublisherBaseCamera(sensor_actor_definition, transform_publisher) {} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeRGBCameraPublisher.h b/LibCarla/source/carla/ros2/publishers/UeRGBCameraPublisher.h new file mode 100644 index 00000000000..724689c97a1 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeRGBCameraPublisher.h @@ -0,0 +1,21 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/UePublisherBaseCamera.h" +#include "sensor_msgs/msg/CameraInfoPubSubTypes.h" +#include "sensor_msgs/msg/ImagePubSubTypes.h" + +namespace carla { +namespace ros2 { + +class UeRGBCameraPublisher : public UePublisherBaseCamera { +public: + UeRGBCameraPublisher(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher); + virtual ~UeRGBCameraPublisher() = default; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeRadarPublisher.cpp b/LibCarla/source/carla/ros2/publishers/UeRadarPublisher.cpp new file mode 100644 index 00000000000..b48481c470c --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeRadarPublisher.cpp @@ -0,0 +1,84 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "UeRadarPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" +#include "carla/sensor/data/RadarData.h" + +namespace carla { +namespace ros2 { + + struct RadarDetectionWithPosition { + float x; + float y; + float z; + carla::sensor::data::RadarDetection detection; + }; + + + +UeRadarPublisher::UeRadarPublisher(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher) + : UePublisherBasePointCloud(sensor_actor_definition, transform_publisher) {} + +std::vector UeRadarPublisher::GetPointFields() const { + sensor_msgs::msg::PointField descriptor1; + descriptor1.name("x"); + descriptor1.offset(0); + descriptor1.datatype(sensor_msgs::msg::PointField__FLOAT32); + descriptor1.count(1); + sensor_msgs::msg::PointField descriptor2; + descriptor2.name("y"); + descriptor2.offset(4); + descriptor2.datatype(sensor_msgs::msg::PointField__FLOAT32); + descriptor2.count(1); + sensor_msgs::msg::PointField descriptor3; + descriptor3.name("z"); + descriptor3.offset(8); + descriptor3.datatype(sensor_msgs::msg::PointField__FLOAT32); + descriptor3.count(1); + sensor_msgs::msg::PointField descriptor4; + descriptor4.name("velocity"); + descriptor4.offset(12); + descriptor4.datatype(sensor_msgs::msg::PointField__FLOAT32); + descriptor4.count(1); + sensor_msgs::msg::PointField descriptor5; + descriptor5.name("azimuth"); + descriptor5.offset(16); + descriptor5.datatype(sensor_msgs::msg::PointField__FLOAT32); + descriptor5.count(1); + sensor_msgs::msg::PointField descriptor6; + descriptor6.name("altitude"); + descriptor6.offset(20); + descriptor6.datatype(sensor_msgs::msg::PointField__FLOAT32); + descriptor6.count(1); + sensor_msgs::msg::PointField descriptor7; + descriptor7.name("depth"); + descriptor7.offset(24); + descriptor7.datatype(sensor_msgs::msg::PointField__FLOAT32); + descriptor7.count(1); + return {descriptor1, descriptor2, descriptor3, descriptor4, descriptor5, descriptor6, descriptor7}; +} + +size_t UeRadarPublisher::GetMessagePointSize() const { + return sizeof(RadarDetectionWithPosition); +} + +void UeRadarPublisher::SetPointCloudDataFromBuffer(std::shared_ptr, + std::vector data_vector_view) { + _point_cloud->Message().data().resize(data_vector_view.size() * sizeof(RadarDetectionWithPosition) / sizeof(uint8_t)); + auto point_clound_data_iter = reinterpret_cast(_point_cloud->Message().data().data()); + for (auto const &data_view : data_vector_view) { + RadarDetectionWithPosition ros_data; + ros_data.x = data_view.depth * cosf(data_view.azimuth) * cosf(-data_view.altitude); + ros_data.y = data_view.depth * sinf(-data_view.azimuth) * cosf(data_view.altitude); + ros_data.z = data_view.depth * sinf(data_view.altitude); + ros_data.detection = data_view; + *point_clound_data_iter = ros_data; + ++point_clound_data_iter; + } +} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeRadarPublisher.h b/LibCarla/source/carla/ros2/publishers/UeRadarPublisher.h new file mode 100644 index 00000000000..48660a3ab37 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeRadarPublisher.h @@ -0,0 +1,51 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/UePublisherBasePointCloud.h" +#include "carla/sensor/s11n/RadarSerializer.h" + +namespace carla { +namespace ros2 { + +/// A view over the header of a Lidar measurement. +class RadarDummyHeaderView { +public: + size_t GetHeaderOffset() const { + return 0u; + } + float GetHorizontalAngle() const { + return 0.f; + } + uint32_t GetChannelCount() const { + return 0u; + } + + uint32_t GetPointCount(size_t) const { + return 0u; + } + + size_t GetDataSize() const { + return 0u; + } + + RadarDummyHeaderView(const uint32_t *) {} +}; + +class UeRadarPublisher : public UePublisherBasePointCloud { +public: + UeRadarPublisher(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher); + virtual ~UeRadarPublisher() = default; + +protected: + std::vector GetPointFields() const override; + size_t GetMessagePointSize() const override; + + void SetPointCloudDataFromBuffer(std::shared_ptr header_view, + std::vector vector_view) override; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeSSCameraPublisher.cpp b/LibCarla/source/carla/ros2/publishers/UeSSCameraPublisher.cpp new file mode 100644 index 00000000000..e8ce33a6820 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeSSCameraPublisher.cpp @@ -0,0 +1,17 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "UeSSCameraPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +UeSSCameraPublisher::UeSSCameraPublisher( + std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher) + : UePublisherBaseCamera(sensor_actor_definition, transform_publisher) {} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeSSCameraPublisher.h b/LibCarla/source/carla/ros2/publishers/UeSSCameraPublisher.h new file mode 100644 index 00000000000..f511a114e32 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeSSCameraPublisher.h @@ -0,0 +1,21 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/UePublisherBaseCamera.h" +#include "sensor_msgs/msg/CameraInfoPubSubTypes.h" +#include "sensor_msgs/msg/ImagePubSubTypes.h" + +namespace carla { +namespace ros2 { + +class UeSSCameraPublisher : public UePublisherBaseCamera { +public: + UeSSCameraPublisher(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher); + virtual ~UeSSCameraPublisher() = default; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeSemanticLidarPublisher.cpp b/LibCarla/source/carla/ros2/publishers/UeSemanticLidarPublisher.cpp new file mode 100644 index 00000000000..22e8f59b0a2 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeSemanticLidarPublisher.cpp @@ -0,0 +1,68 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "UeSemanticLidarPublisher.h" + +#include "carla/Debug.h" +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +UeSemanticLidarPublisher::UeSemanticLidarPublisher( + std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher) + : UePublisherBasePointCloud(sensor_actor_definition, transform_publisher) {} + +std::vector UeSemanticLidarPublisher::GetPointFields() const { + sensor_msgs::msg::PointField descriptor1; + descriptor1.name("x"); + descriptor1.offset(0); + descriptor1.datatype(sensor_msgs::msg::PointField__FLOAT32); + descriptor1.count(1); + sensor_msgs::msg::PointField descriptor2; + descriptor2.name("y"); + descriptor2.offset(4); + descriptor2.datatype(sensor_msgs::msg::PointField__FLOAT32); + descriptor2.count(1); + sensor_msgs::msg::PointField descriptor3; + descriptor3.name("z"); + descriptor3.offset(8); + descriptor3.datatype(sensor_msgs::msg::PointField__FLOAT32); + descriptor3.count(1); + sensor_msgs::msg::PointField descriptor4; + descriptor4.name("cos_inc_angle"); + descriptor4.offset(12); + descriptor4.datatype(sensor_msgs::msg::PointField__FLOAT32); + descriptor4.count(1); + sensor_msgs::msg::PointField descriptor5; + descriptor5.name("object_idx"); + descriptor5.offset(16); + descriptor5.datatype(sensor_msgs::msg::PointField__UINT32); + descriptor5.count(1); + sensor_msgs::msg::PointField descriptor6; + descriptor6.name("object_tag"); + descriptor6.offset(20); + descriptor6.datatype(sensor_msgs::msg::PointField__UINT32); + descriptor6.count(1); + + return {descriptor1, descriptor2, descriptor3, descriptor4, descriptor5, descriptor6}; +} + +void UeSemanticLidarPublisher::SetPointCloudDataFromBuffer(std::shared_ptr header_view, + std::vector vector_view) { + DEBUG_ASSERT_EQ(header_view->GetChannelCount(), 6); + DEBUG_ASSERT_EQ(sizeof(SemanticLidarDetection), 4 * sizeof(float) + 2 * sizeof(uint32_t)); + + _point_cloud->Message().data().resize(vector_view.size() * sizeof(SemanticLidarDetection) / sizeof(uint8_t)); + auto point_clound_data_iter = reinterpret_cast(_point_cloud->Message().data().data()); + for (auto const &data_view : vector_view) { + SemanticLidarDetection ros_data(CoordinateSystemTransform::TransformLinearAxixVector3D(data_view.point), + data_view.cos_inc_angle, data_view.object_idx, data_view.object_tag); + *point_clound_data_iter = ros_data; + ++point_clound_data_iter; + } +} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeSemanticLidarPublisher.h b/LibCarla/source/carla/ros2/publishers/UeSemanticLidarPublisher.h new file mode 100644 index 00000000000..f54f163579f --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeSemanticLidarPublisher.h @@ -0,0 +1,28 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/UePublisherBasePointCloud.h" +#include "carla/sensor/s11n/SemanticLidarSerializer.h" + +namespace carla { +namespace ros2 { + +class UeSemanticLidarPublisher : public UePublisherBasePointCloud { +public: + UeSemanticLidarPublisher(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher); + virtual ~UeSemanticLidarPublisher() = default; + +protected: + using SemanticLidarDetection = DataType; + std::vector GetPointFields() const override; + + void SetPointCloudDataFromBuffer(std::shared_ptr header_view, + std::vector vector_view) override; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeV2XCustomPublisher.cpp b/LibCarla/source/carla/ros2/publishers/UeV2XCustomPublisher.cpp new file mode 100644 index 00000000000..871add92d22 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeV2XCustomPublisher.cpp @@ -0,0 +1,65 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "UeV2XCustomPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +UeV2XCustomPublisher::UeV2XCustomPublisher(std::shared_ptr sensor_actor_definition, + carla::ros2::types::V2XCustomSendCallback v2x_custom_send_callback, + std::shared_ptr transform_publisher) + : UePublisherBaseSensor(sensor_actor_definition, transform_publisher), + _subscriber(std::make_shared(*this, v2x_custom_send_callback)), + _impl(std::make_shared()) {} + +bool UeV2XCustomPublisher::Init(std::shared_ptr domain_participant) { + _initialized = _impl->InitHistoryPreallocatedWithReallocMemoryMode(domain_participant, get_topic_name(), get_topic_qos().reliable()) && _subscriber->Init(domain_participant); + return _initialized; +} + +bool UeV2XCustomPublisher::Publish() { + return _impl->Publish(); +} +bool UeV2XCustomPublisher::SubscribersConnected() const { + return _impl->SubscribersConnected(); +} + +void UeV2XCustomPublisher::UpdateSensorDataPreAction() +{ + if (!_initialized) { + return; + } + _subscriber->ProcessMessages(); +} + +void UeV2XCustomPublisher::UpdateSensorData( + std::shared_ptr sensor_header, + carla::SharedBufferView buffer_view) { + + auto custom_v2x_data_vector = vector_view(buffer_view); + + if ( _impl->WasMessagePublished() ) { + _impl->Message().data().clear(); + } + + for (carla::sensor::data::CustomV2XData const &custom_v2x_data: custom_v2x_data_vector) { + carla_msgs::msg::CarlaV2XCustomData carla_v2x_custom_data; + carla_v2x_custom_data.power(custom_v2x_data.Power); + carla_msgs::msg::CarlaV2XCustomMessage carla_v2x_custom_message; + carla_v2x_custom_message.header().protocol_version() = custom_v2x_data.Message.header.protocolVersion; + carla_v2x_custom_message.header().message_id() = custom_v2x_data.Message.header.messageID; + carla_v2x_custom_message.header().station_id().value() = custom_v2x_data.Message.header.stationID; + carla_v2x_custom_message.data().data_size() = custom_v2x_data.Message.data.data_size; + carla_v2x_custom_message.data().bytes() = custom_v2x_data.Message.data.bytes; + carla_v2x_custom_data.message() = carla_v2x_custom_message; + _impl->Message().data().push_back(carla_v2x_custom_data); + } + _impl->SetMessageUpdated(); +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeV2XCustomPublisher.h b/LibCarla/source/carla/ros2/publishers/UeV2XCustomPublisher.h new file mode 100644 index 00000000000..3e5b8861ca4 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeV2XCustomPublisher.h @@ -0,0 +1,65 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include + +#include "carla/ros2/publishers/UePublisherBaseSensor.h" +#include "carla/ros2/subscribers/UeV2XCustomSubscriber.h" +#include "carla/sensor/data/V2XEvent.h" +#include "carla_msgs/msg/CarlaV2XCustomDataListPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using UeV2XCustomPublisherImpl = DdsPublisherImpl; + +class UeV2XCustomPublisher : public UePublisherBaseSensor { +public: + UeV2XCustomPublisher(std::shared_ptr sensor_actor_definition, + carla::ros2::types::V2XCustomSendCallback v2x_custom_send_callback, + std::shared_ptr transform_publisher); + virtual ~UeV2XCustomPublisher() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + /** + * Implement UePublisherBaseSensor::UpdateSensorDataPreAction() + */ + void UpdateSensorDataPreAction() override; + /** + * Implements UePublisherBaseSensor::UpdateSensorData() interface + */ + void UpdateSensorData(std::shared_ptr sensor_header, + const carla::SharedBufferView buffer_view) override; + +private: + using CustomV2XData = carla::sensor::data::CustomV2XData; + using CustomV2XDataVectorAllocator = carla::sensor::data::SerializerVectorAllocator; + + std::vector vector_view(const carla::SharedBufferView buffer_view) { + return carla::sensor::data::buffer_data_accessed_by_vector( + buffer_view, 0); + } + + + bool _initialized{false}; + std::shared_ptr _subscriber; + std::shared_ptr _impl; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeV2XPublisher.cpp b/LibCarla/source/carla/ros2/publishers/UeV2XPublisher.cpp new file mode 100644 index 00000000000..29a49c43885 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeV2XPublisher.cpp @@ -0,0 +1,159 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "UeV2XPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +UeV2XPublisher::UeV2XPublisher(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher) + : UePublisherBaseSensor(sensor_actor_definition, transform_publisher), + _impl(std::make_shared()) {} + +bool UeV2XPublisher::Init(std::shared_ptr domain_participant) { + _initialized = _impl->InitHistoryPreallocatedWithReallocMemoryMode(domain_participant, get_topic_name(), get_topic_qos().reliable()); + return _initialized; +} + +bool UeV2XPublisher::Publish() { + return _impl->Publish(); +} +bool UeV2XPublisher::SubscribersConnected() const { + return _impl->SubscribersConnected(); +} + +void UeV2XPublisher::UpdateSensorData( + std::shared_ptr sensor_header, + carla::SharedBufferView buffer_view) { + + auto cam_v2x_data_vector = vector_view(buffer_view); + + if ( _impl->WasMessagePublished() ) { + _impl->Message().data().clear(); + } + + for (carla::sensor::data::CAMData const &cam_v2x_data: cam_v2x_data_vector) { + // General data and header + carla_msgs::msg::CarlaV2XData carla_v2x_data; + carla_v2x_data.power(cam_v2x_data.Power); + carla_v2x_data.message().header().protocol_version() = cam_v2x_data.Message.header.protocolVersion; + carla_v2x_data.message().header().message_id() = cam_v2x_data.Message.header.messageID; + carla_v2x_data.message().header().station_id().value() = cam_v2x_data.Message.header.stationID; + carla_v2x_data.message().cam().generation_delta_time().value() = cam_v2x_data.Message.cam.generationDeltaTime; + + // BasicContainer + carla_v2x_data.message().cam().cam_parameters().basic_container().reference_position().altitude().altitude_value().value() = cam_v2x_data.Message.cam.camParameters.basicContainer.referencePosition.altitude.altitudeValue; + carla_v2x_data.message().cam().cam_parameters().basic_container().reference_position().altitude().altitude_confidence().value() = cam_v2x_data.Message.cam.camParameters.basicContainer.referencePosition.altitude.altitudeConfidence; + carla_v2x_data.message().cam().cam_parameters().basic_container().reference_position().latitude().value() = cam_v2x_data.Message.cam.camParameters.basicContainer.referencePosition.latitude; + carla_v2x_data.message().cam().cam_parameters().basic_container().reference_position().longitude().value() = cam_v2x_data.Message.cam.camParameters.basicContainer.referencePosition.longitude; + carla_v2x_data.message().cam().cam_parameters().basic_container().reference_position().position_confidence_ellipse().semi_major_confidence().value() = cam_v2x_data.Message.cam.camParameters.basicContainer.referencePosition.positionConfidenceEllipse.semiMajorConfidence; + carla_v2x_data.message().cam().cam_parameters().basic_container().reference_position().position_confidence_ellipse().semi_major_orientation().value() = cam_v2x_data.Message.cam.camParameters.basicContainer.referencePosition.positionConfidenceEllipse.semiMajorOrientation; + carla_v2x_data.message().cam().cam_parameters().basic_container().reference_position().position_confidence_ellipse().semi_minor_confidence().value() = cam_v2x_data.Message.cam.camParameters.basicContainer.referencePosition.positionConfidenceEllipse.semiMinorConfidence; + carla_v2x_data.message().cam().cam_parameters().basic_container().station_type().value() = cam_v2x_data.Message.cam.camParameters.basicContainer.stationType; + + // HighFrequencyContainer + switch (cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.present) { + case CAMContainer::HighFrequencyContainer_PR::HighFrequencyContainer_PR_basicVehicleContainerHighFrequency: + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().choice() = etsi_its_cam_msgs::msg::HighFrequencyContainer_Constants::CHOICE_BASIC_VEHICLE_CONTAINER_HIGH_FREQUENCY; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().heading().heading_value().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.heading.headingValue; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().heading().heading_confidence().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.heading.headingConfidence; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().speed().speed_value().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.speed.speedValue; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().speed().speed_confidence().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.speed.speedConfidence; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().drive_direction().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.driveDirection; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().vehicle_length().vehicle_length_value().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.vehicleLength.vehicleLengthValue; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().vehicle_length().vehicle_length_confidence_indication().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.vehicleLength.vehicleLengthConfidenceIndication; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().vehicle_width().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.vehicleWidth; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().longitudinal_acceleration().longitudinal_acceleration_confidence().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.longitudinalAcceleration.longitudinalAccelerationConfidence; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().longitudinal_acceleration().longitudinal_acceleration_value().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.longitudinalAcceleration.longitudinalAccelerationValue; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().curvature().curvature_value().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.curvature.curvatureValue; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().curvature().curvature_confidence().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.curvature.curvatureConfidence; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().curvature_calculation_mode().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.curvatureCalculationMode; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().yaw_rate().yaw_rate_value().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.yawRate.yawRateValue; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().yaw_rate().yaw_rate_confidence().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.yawRate.yawRateConfidence; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().acceleration_control_is_present() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.accelerationControlAvailable; + // TODO: carla implemenation differs from CAM definition, since ASN.1 defines a list + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().acceleration_control().value().push_back(cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.accelerationControl); + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().lane_position_is_present() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.lanePositionAvailable; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().lane_position().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.lanePosition; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().steering_wheel_angle_is_present() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.steeringWheelAngleAvailable; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().steering_wheel_angle().steering_wheel_angle_value().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.steeringWheelAngle.steeringWheelAngleValue; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().steering_wheel_angle().steering_wheel_angle_confidence().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.steeringWheelAngle.steeringWheelAngleConfidence; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().lateral_acceleration_is_present() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.lateralAccelerationAvailable; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().lateral_acceleration().lateral_acceleration_value().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.lateralAcceleration.lateralAccelerationValue; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().lateral_acceleration().lateral_acceleration_confidence().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.lateralAcceleration.lateralAccelerationConfidence; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().vertical_acceleration_is_present() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.verticalAccelerationAvailable; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().vertical_acceleration().vertical_acceleration_value().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.verticalAcceleration.verticalAccelerationValue; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().vertical_acceleration().vertical_acceleration_confidence().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.verticalAcceleration.verticalAccelerationConfidence; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().performance_class_is_present() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.performanceClassAvailable; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().performance_class().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.performanceClass; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().cen_dsrc_tolling_zone_is_present() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.cenDsrcTollingZoneAvailable; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().cen_dsrc_tolling_zone().cen_dsrc_tolling_zone_id_is_present() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.cenDsrcTollingZone.cenDsrcTollingZoneIDAvailable; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().cen_dsrc_tolling_zone().cen_dsrc_tolling_zone_id().value().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.cenDsrcTollingZone.cenDsrcTollingZoneID; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().cen_dsrc_tolling_zone().protected_zone_latitude().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.cenDsrcTollingZone.protectedZoneLatitude; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().basic_vehicle_container_high_frequency().cen_dsrc_tolling_zone().protected_zone_longitude().value() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency.cenDsrcTollingZone.protectedZoneLongitude; + break; + case CAMContainer::HighFrequencyContainer_PR::HighFrequencyContainer_PR_rsuContainerHighFrequency: + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().choice() = etsi_its_cam_msgs::msg::HighFrequencyContainer_Constants::CHOICE_BASIC_VEHICLE_CONTAINER_HIGH_FREQUENCY; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().rsu_container_high_frequency().protected_communication_zones_rsu_is_present() = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.rsuContainerHighFrequency.protectedCommunicationZonesRSU.ProtectedCommunicationZoneCount > 0u; + for (auto i=0u; i< cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.rsuContainerHighFrequency.protectedCommunicationZonesRSU.ProtectedCommunicationZoneCount; ++i) { + auto const &protectedCommunicationZoneRSU = cam_v2x_data.Message.cam.camParameters.highFrequencyContainer.rsuContainerHighFrequency.protectedCommunicationZonesRSU.data[i]; + etsi_its_cam_msgs::msg::ProtectedCommunicationZone protectedCommunicationZone; + protectedCommunicationZone.expiry_time_is_present() = protectedCommunicationZoneRSU.expiryTimeAvailable; + protectedCommunicationZone.expiry_time().value() = protectedCommunicationZoneRSU.expiryTime; + protectedCommunicationZone.protected_zone_id_is_present() = protectedCommunicationZoneRSU.protectedZoneIDAvailable; + protectedCommunicationZone.protected_zone_id().value() = protectedCommunicationZoneRSU.protectedZoneID; + protectedCommunicationZone.protected_zone_latitude().value() = protectedCommunicationZoneRSU.protectedZoneLatitude; + protectedCommunicationZone.protected_zone_longitude().value() = protectedCommunicationZoneRSU.protectedZoneLongitude; + protectedCommunicationZone.protected_zone_radius_is_present() = protectedCommunicationZoneRSU.protectedZoneRadiusAvailable; + protectedCommunicationZone.protected_zone_radius().value() = protectedCommunicationZoneRSU.protectedZoneRadius; + protectedCommunicationZone.protected_zone_type().value() = protectedCommunicationZoneRSU.protectedZoneType; + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().rsu_container_high_frequency().protected_communication_zones_rsu().array().push_back(protectedCommunicationZone); + } + break; + case CAMContainer::HighFrequencyContainer_PR::HighFrequencyContainer_PR_NOTHING: + // theorectically must not happen, since in the protocol Nothing is not defined and is translated into high_fequency_container_is_present, which is also not defined by the actual protocol! + carla_v2x_data.message().cam().cam_parameters().high_frequency_container().choice() = etsi_its_cam_msgs::msg::HighFrequencyContainer_Constants::CHOICE_BASIC_VEHICLE_CONTAINER_HIGH_FREQUENCY; + break; + } + + // LowFrequencyContainer + switch (cam_v2x_data.Message.cam.camParameters.lowFrequencyContainer.present) { + case CAMContainer::LowFrequencyContainer_PR::LowFrequencyContainer_PR_NOTHING: + carla_v2x_data.message().cam().cam_parameters().low_frequency_container_is_present() = false; + break; + case CAMContainer::LowFrequencyContainer_PR::LowFrequencyContainer_PR_basicVehicleContainerLowFrequency: + carla_v2x_data.message().cam().cam_parameters().low_frequency_container_is_present() = true; + carla_v2x_data.message().cam().cam_parameters().low_frequency_container().choice() = etsi_its_cam_msgs::msg::LowFrequencyContainer_Constants::CHOICE_BASIC_VEHICLE_CONTAINER_LOW_FREQUENCY; + // TODO: carla implemenation differs from CAM definition, since ASN.1 defines a list + carla_v2x_data.message().cam().cam_parameters().low_frequency_container().basic_vehicle_container_low_frequency().exterior_lights().value().push_back(cam_v2x_data.Message.cam.camParameters.lowFrequencyContainer.basicVehicleContainerLowFrequency.exteriorLights); + for (auto i=0u; i< cam_v2x_data.Message.cam.camParameters.lowFrequencyContainer.basicVehicleContainerLowFrequency.pathHistory.NumberOfPathPoint; ++i) { + auto const &pathPointCarla = cam_v2x_data.Message.cam.camParameters.lowFrequencyContainer.basicVehicleContainerLowFrequency.pathHistory.data[i]; + etsi_its_cam_msgs::msg::PathPoint pathPoint; + pathPoint.path_delta_time_is_present() = false; + if (pathPointCarla.pathDeltaTime != nullptr) { + pathPoint.path_delta_time_is_present() = true; + pathPoint.path_delta_time().value() = *pathPointCarla.pathDeltaTime; + } + pathPoint.path_position().delta_longitude().value() = pathPointCarla.pathPosition.deltaLongitude; + pathPoint.path_position().delta_latitude().value() = pathPointCarla.pathPosition.deltaLatitude; + pathPoint.path_position().delta_altitude().value() = pathPointCarla.pathPosition.deltaAltitude; + carla_v2x_data.message().cam().cam_parameters().low_frequency_container().basic_vehicle_container_low_frequency().path_history().array().push_back(pathPoint); + } + carla_v2x_data.message().cam().cam_parameters().low_frequency_container().basic_vehicle_container_low_frequency().vehicle_role().value() = cam_v2x_data.Message.cam.camParameters.lowFrequencyContainer.basicVehicleContainerLowFrequency.vehicleRole; + } + + // TODO: SpecialVehiclesContainer + carla_v2x_data.message().cam().cam_parameters().special_vehicle_container_is_present() = false; + + // Finally send out + _impl->Message().data().push_back(carla_v2x_data); + } + _impl->SetMessageUpdated(); +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeV2XPublisher.h b/LibCarla/source/carla/ros2/publishers/UeV2XPublisher.h new file mode 100644 index 00000000000..a4066d0c80f --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeV2XPublisher.h @@ -0,0 +1,58 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include + +#include "carla/ros2/publishers/UePublisherBaseSensor.h" +#include "carla/sensor/data/V2XEvent.h" +#include "carla_msgs/msg/CarlaV2XDataListPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using UeV2XPublisherImpl = DdsPublisherImpl; + +class UeV2XPublisher : public UePublisherBaseSensor { +public: + UeV2XPublisher(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher); + virtual ~UeV2XPublisher() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + /** + * Implements UePublisherBaseSensor::UpdateSensorData() interface + */ + void UpdateSensorData(std::shared_ptr sensor_header, + const carla::SharedBufferView buffer_view) override; + +private: + using CAMData = carla::sensor::data::CAMData; + using CAMDataVectorAllocator = carla::sensor::data::SerializerVectorAllocator; + + std::vector vector_view(const carla::SharedBufferView buffer_view) { + return carla::sensor::data::buffer_data_accessed_by_vector( + buffer_view, 0); + } + + + bool _initialized{false}; + std::shared_ptr _impl; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeWorldPublisher.cpp b/LibCarla/source/carla/ros2/publishers/UeWorldPublisher.cpp new file mode 100644 index 00000000000..236a47e08d5 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeWorldPublisher.cpp @@ -0,0 +1,464 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "UeWorldPublisher.h" + +#include "carla/sensor/data/RawEpisodeState.h" +#include "carla/ros2/types/EpisodeSettings.h" + +namespace carla { +namespace ros2 { + +UeWorldPublisher::UeWorldPublisher(carla::rpc::RpcServerInterface& carla_server, + std::shared_ptr name_registry, + std::shared_ptr sensor_actor_definition) + : UePublisherBaseSensor(sensor_actor_definition, std::make_shared()), + _carla_server(carla_server), + _name_registry(name_registry), + _carla_status_publisher(std::make_shared()), + _carla_actor_list_publisher(std::make_shared("actor_list")), + _clock_publisher(std::make_shared()), + _map_publisher(std::make_shared()), + _objects_publisher(std::make_shared()), + _objects_with_covariance_publisher(std::make_shared()), + _traffic_lights_publisher(std::make_shared()), + _carla_control_subscriber(std::make_shared(*this, _carla_server)), + _sync_subscriber(std::make_shared(*this, _carla_server)) { +} + +bool UeWorldPublisher::Init(std::shared_ptr domain_participant) { + _domain_participant_impl = domain_participant; + _initialized = _carla_status_publisher->Init(domain_participant) && + _carla_actor_list_publisher->Init(domain_participant) && _clock_publisher->Init(domain_participant) && + _map_publisher->Init(domain_participant) && _objects_publisher->Init(domain_participant) && + _objects_with_covariance_publisher->Init(domain_participant) && _traffic_lights_publisher->Init(domain_participant) && + _transform_publisher->Init(domain_participant) && + _carla_control_subscriber->Init(domain_participant) && _sync_subscriber->Init(domain_participant); + return _initialized; +} + +bool UeWorldPublisher::Publish() { + if (!_initialized) { + return false; + } + return _clock_publisher->Publish() && _map_publisher->Publish(); +} + +void UeWorldPublisher::ProcessMessages() { + if (!_initialized) { + return; + } + + _carla_control_subscriber->ProcessMessages(); + _sync_subscriber->ProcessMessages(); + for (auto& vehicle : _vehicles) { + vehicle.second._vehicle_controller->ProcessMessages(); + vehicle.second._vehicle_ackermann_controller->ProcessMessages(); + vehicle.second._actor_set_transform_subscriber->ProcessMessages(); + } + for (auto& walker : _walkers) { + walker.second._walker_controller->ProcessMessages(); + } + + UpdateAndPublishStatus(); +} + +void UeWorldPublisher::UpdateSensorDataPostAction() { + if (!_initialized) { + return; + } + + UpdateAndPublishStatus(); + + _transform_publisher->Publish(); + + if (_carla_actor_list_publisher->SubscribersConnected()) { + _carla_actor_list_publisher->Publish(); + } + if (_objects_publisher->SubscribersConnected()) { + _objects_publisher->Publish(); + } + if (_objects_with_covariance_publisher->SubscribersConnected()) { + _objects_with_covariance_publisher->Publish(); + } + if (_traffic_lights_publisher->SubscribersConnected()) { + _traffic_lights_publisher->Publish(); + } +} + +void UeWorldPublisher::AddVehicleUe( + std::shared_ptr vehicle_actor_definition, + carla::ros2::types::VehicleControlCallback vehicle_control_callback, + carla::ros2::types::VehicleAckermannControlCallback vehicle_ackermann_control_callback, + carla::ros2::types::ActorSetTransformCallback vehicle_set_transform_callback) { + if (!_initialized) { + return; + } + + auto object = std::make_shared(vehicle_actor_definition); + auto object_result = _objects.insert({vehicle_actor_definition->id, object}); + if (!object_result.second) { + object_result.first->second = object; + } + _objects_changed = true; + + auto vehicle_publisher = + std::make_shared(vehicle_actor_definition, _transform_publisher, _objects_publisher, _objects_with_covariance_publisher); + UeVehicle ue_vehicle(vehicle_publisher); + ue_vehicle._vehicle_controller = + std::make_shared(*vehicle_publisher, std::move(vehicle_control_callback)); + ue_vehicle._vehicle_ackermann_controller = + std::make_shared(*vehicle_publisher, std::move(vehicle_ackermann_control_callback)); + ue_vehicle._actor_set_transform_subscriber = + std::make_shared(*vehicle_publisher, std::move(vehicle_set_transform_callback)); + + auto vehicle_result = _vehicles.insert({vehicle_actor_definition->id, ue_vehicle}); + if (!vehicle_result.second) { + vehicle_result.first->second = std::move(ue_vehicle); + } + vehicle_result.first->second.Init(_domain_participant_impl); +} + +void UeWorldPublisher::UeVehicle::Init(std::shared_ptr domain_participant) +{ + if ( _vehicle_publisher->is_enabled_for_ros() ) { + _vehicle_publisher->Init(domain_participant); + _vehicle_controller->Init(domain_participant); + _vehicle_ackermann_controller->Init(domain_participant); + _actor_set_transform_subscriber->Init(domain_participant); + } +} + +void UeWorldPublisher::AddWalkerUe(std::shared_ptr walker_actor_definition, + carla::ros2::types::WalkerControlCallback walker_control_callback) { + if (!_initialized) { + return; + } + auto object = std::make_shared(walker_actor_definition); + auto object_result = _objects.insert({walker_actor_definition->id, object}); + if (!object_result.second) { + object_result.first->second = object; + } + _objects_changed = true; + + auto walker_publisher = + std::make_shared(walker_actor_definition, _transform_publisher, _objects_publisher, _objects_with_covariance_publisher); + UeWalker ue_walker(walker_publisher); + ue_walker._walker_controller = + std::make_shared(*walker_publisher, std::move(walker_control_callback)); + + auto walker_result = _walkers.insert({walker_actor_definition->id, ue_walker}); + if (!walker_result.second) { + walker_result.first->second = std::move(ue_walker); + } + + walker_result.first->second.Init(_domain_participant_impl); +} + +void UeWorldPublisher::UeWalker::Init(std::shared_ptr domain_participant) +{ + if ( _walker_publisher->is_enabled_for_ros() ) { + _walker_publisher->Init(domain_participant); + _walker_controller->Init(domain_participant); + } +} + +void UeWorldPublisher::AddTrafficLightUe( + std::shared_ptr traffic_light_actor_definition) { + auto object = std::make_shared(traffic_light_actor_definition); + if (!_initialized) { + return; + } + auto object_result = _objects.insert({traffic_light_actor_definition->id, object}); + if (!object_result.second) { + object_result.first->second = object; + } + _objects_changed = true; + + auto traffic_light_publisher = std::make_shared(traffic_light_actor_definition, + _objects_publisher, _objects_with_covariance_publisher, _traffic_lights_publisher); + UeTrafficLight ue_traffic_light(traffic_light_publisher); + auto traffic_light_result = _traffic_lights.insert({traffic_light_actor_definition->id, ue_traffic_light}); + if (!traffic_light_result.second) { + traffic_light_result.first->second = std::move(ue_traffic_light); + } + + traffic_light_result.first->second.Init(_domain_participant_impl); +} + +void UeWorldPublisher::UeTrafficLight::Init(std::shared_ptr domain_participant) +{ + if ( _traffic_light_publisher->is_enabled_for_ros() ) { + _traffic_light_publisher->Init(domain_participant); + } +} + +void UeWorldPublisher::AddTrafficSignUe( + std::shared_ptr traffic_sign_actor_definition) { + if (!_initialized) { + return; + } + auto object = std::make_shared(traffic_sign_actor_definition); + auto object_result = _objects.insert({traffic_sign_actor_definition->id, object}); + if (!object_result.second) { + object_result.first->second = object; + } + _objects_changed = true; + + auto traffic_sign_publisher = + std::make_shared(traffic_sign_actor_definition, _objects_publisher, _objects_with_covariance_publisher); + UeTrafficSign ue_traffic_sign(traffic_sign_publisher); + auto traffic_sign_result = _traffic_signs.insert({traffic_sign_actor_definition->id, ue_traffic_sign}); + if (!traffic_sign_result.second) { + traffic_sign_result.first->second = std::move(ue_traffic_sign); + } + + traffic_sign_result.first->second.Init(_domain_participant_impl); +} + +void UeWorldPublisher::UeTrafficSign::Init(std::shared_ptr domain_participant) +{ + if ( _traffic_sign_publisher->is_enabled_for_ros() ) { + _traffic_sign_publisher->Init(domain_participant); + } +} + +void UeWorldPublisher::RemoveActor(ActorId actor) { + if (!_initialized) { + return; + } + _objects.erase(actor); + _objects_changed = true; + auto vehicle_iter = _vehicles.find(actor); + if ( vehicle_iter != _vehicles.end() ) { + log_warning("ROS2::RemoveVehicleUe(", std::to_string( + *std::static_pointer_cast(vehicle_iter->second._vehicle_publisher->_actor_name_definition)), ")"); + _vehicles.erase(vehicle_iter); + } + auto walker_iter = _walkers.find(actor); + if ( walker_iter != _walkers.end() ) { + log_warning("ROS2::RemoveWalkerUe(", std::to_string( + *std::static_pointer_cast(walker_iter->second._walker_publisher->_actor_name_definition)), ")"); + _walkers.erase(walker_iter); + } + auto traffic_light_iter = _traffic_lights.find(actor); + if ( traffic_light_iter != _traffic_lights.end() ) { + log_warning("ROS2::RemoveTrafficLightUe(", std::to_string( + *std::static_pointer_cast(traffic_light_iter->second._traffic_light_publisher->_actor_name_definition)), ")"); + _traffic_lights.erase(traffic_light_iter); + } + _traffic_lights_publisher->RemoveTrafficLight(actor); + + auto traffic_sign_iter = _traffic_signs.find(actor); + if ( traffic_sign_iter != _traffic_signs.end() ) { + log_warning("ROS2::RemoveTrafficSignUe(", std::to_string( + *std::static_pointer_cast(traffic_sign_iter->second._traffic_sign_publisher->_actor_name_definition)), ")"); + _traffic_signs.erase(traffic_sign_iter); + } +} + +void UeWorldPublisher::UpdateAndPublishStatus() { + auto const synchronization_window_status = _carla_server.call_get_synchronization_window_status(); + if (_frame_changed || synchronization_window_status.Get().first) { + _frame_changed = false; + carla_msgs::msg::CarlaStatus status; + status.frame(_frame); + carla::ros2::types::EpisodeSettings carla_episode_settings(_carla_server.call_get_episode_settings().Get()); + status.episode_settings( carla_episode_settings.episode_settings()); + status.header().stamp(_timestamp.time()); + status.header().frame_id(""); + status.synchronous_mode_participant_states().reserve(synchronization_window_status.Get().second.size()); + double synchronization_target_game_time_min = std::numeric_limits::max(); + for ( auto const &synchronization_window_participant_state: synchronization_window_status.Get().second) { + carla_msgs::msg::CarlaSynchronizationWindowParticipantState participant_state; + participant_state.client_id(synchronization_window_participant_state.client_id); + participant_state.participant_id(synchronization_window_participant_state.participant_id); + carla::ros2::types::Timestamp target_game_time(synchronization_window_participant_state.target_game_time); + participant_state.target_game_time(target_game_time.Stamp()); + status.synchronous_mode_participant_states().push_back(participant_state); + if ( target_game_time.Stamp() > 0. ) { + synchronization_target_game_time_min = std::min(synchronization_target_game_time_min, target_game_time.Stamp()); + } + } + + status.game_running(synchronization_target_game_time_min > _timestamp.Stamp()); + _carla_status_publisher->UpdateCarlaStatus(status); + + if (_carla_status_publisher->SubscribersConnected()) { + _carla_status_publisher->Publish(); + } + } +} + +void UeWorldPublisher::UpdateSensorData( + std::shared_ptr sensor_header, + carla::SharedBufferView buffer_view) { + if (!_initialized) { + return; + } + _frame_changed = true; + _frame = sensor_header->frame; + _timestamp = carla::ros2::types::Timestamp(sensor_header->timestamp); + _clock_publisher->UpdateData(_timestamp.time()); + _objects_publisher->UpdateHeader(_timestamp.time()); + _objects_with_covariance_publisher->UpdateHeader(_timestamp.time()); + + _episode_header = *header_view(buffer_view); + + if (_episode_header.simulation_state & carla::sensor::s11n::EpisodeStateSerializer::MapChange) { + _map_publisher->UpdateData(_carla_server.call_get_map_data().Get()); + } + + for (auto const& actor_dynamic_state : buffer_data_2_vector(buffer_view)) { + auto object_it = _objects.find(actor_dynamic_state.id); + std::shared_ptr object = nullptr; + bool object_enabled_for_ros = false; + if (object_it != _objects.end()) { + object = object_it->second; + } + + if (object != nullptr) { + carla::ros2::types::Transform transform(actor_dynamic_state.transform, actor_dynamic_state.quaternion); + auto vehicle_it = _vehicles.find(actor_dynamic_state.id); + if (vehicle_it != _vehicles.end()) { + UeVehicle& ue_vehicle = vehicle_it->second; + auto publisher = ue_vehicle._vehicle_publisher; + if ( publisher->is_enabled_for_ros() ) { + object_enabled_for_ros = true; + publisher->UpdateTransform(_timestamp, transform); + publisher->UpdateVehicle(object, actor_dynamic_state, _carla_server); + if (publisher->SubscribersConnected()) { + publisher->Publish(); + } + } + } + + auto walker_it = _walkers.find(actor_dynamic_state.id); + if (walker_it != _walkers.end()) { + UeWalker& ue_walker = walker_it->second; + auto publisher = ue_walker._walker_publisher; + if ( publisher->is_enabled_for_ros() ) { + object_enabled_for_ros = true; + publisher->UpdateTransform(_timestamp, transform); + publisher->UpdateWalker(object, actor_dynamic_state); + if (publisher->SubscribersConnected()) { + publisher->Publish(); + } + } + } + + auto traffic_sign_it = _traffic_signs.find(actor_dynamic_state.id); + if (traffic_sign_it != _traffic_signs.end()) { + UeTrafficSign& ue_traffic_sign = traffic_sign_it->second; + auto publisher = ue_traffic_sign._traffic_sign_publisher; + if ( publisher->is_enabled_for_ros() ) { + object_enabled_for_ros = true; + publisher->UpdateTrafficSign(object, actor_dynamic_state); + if (publisher->SubscribersConnected()) { + publisher->Publish(); + } + } + } + + auto traffic_light_it = _traffic_lights.find(actor_dynamic_state.id); + if (traffic_light_it != _traffic_lights.end()) { + UeTrafficLight& ue_traffic_light = traffic_light_it->second; + auto publisher = ue_traffic_light._traffic_light_publisher; + if ( publisher->is_enabled_for_ros() ) { + object_enabled_for_ros = true; + publisher->UpdateTrafficLight(object, actor_dynamic_state); + if (publisher->SubscribersConnected()) { + publisher->Publish(); + } + } + } + } + + if ( object_enabled_for_ros ) { + object->UpdateObject(_timestamp, actor_dynamic_state); + } + } + + if (_objects_changed) { + _objects_changed = false; + carla_msgs::msg::CarlaActorList actor_list; + for (auto const& object : _objects) { + actor_list.actors().push_back(object.second->carla_actor_info(_name_registry)); + } + _carla_actor_list_publisher->UpdateCarlaActorList(actor_list); + } +} + +void UeWorldPublisher::enable_for_ros(carla::streaming::detail::actor_id_type actor_id) { + if ( actor_id == _actor_name_definition->id ) { + // the world publisher itself always enabled + return; + } + auto vehicle_it = _vehicles.find(actor_id); + if (vehicle_it != _vehicles.end()) { + vehicle_it->second._vehicle_publisher->enable_for_ros(); + } + auto walker_it = _walkers.find(actor_id); + if (walker_it != _walkers.end()) { + walker_it->second._walker_publisher->enable_for_ros(); + } + auto traffic_sign_it = _traffic_signs.find(actor_id); + if (traffic_sign_it != _traffic_signs.end()) { + traffic_sign_it->second._traffic_sign_publisher->enable_for_ros(); + } + auto traffic_light_it = _traffic_lights.find(actor_id); + if (traffic_light_it != _traffic_lights.end()) { + traffic_light_it->second._traffic_light_publisher->enable_for_ros(); + } +} + +void UeWorldPublisher::disable_for_ros(carla::streaming::detail::actor_id_type actor_id) { + if ( actor_id == _actor_name_definition->id ) { + // the world publisher itself always enabled + return; + } + auto vehicle_it = _vehicles.find(actor_id); + if (vehicle_it != _vehicles.end()) { + vehicle_it->second._vehicle_publisher->disable_for_ros(); + } + auto walker_it = _walkers.find(actor_id); + if (walker_it != _walkers.end()) { + walker_it->second._walker_publisher->disable_for_ros(); + } + auto traffic_sign_it = _traffic_signs.find(actor_id); + if (traffic_sign_it != _traffic_signs.end()) { + traffic_sign_it->second._traffic_sign_publisher->disable_for_ros(); + } + auto traffic_light_it = _traffic_lights.find(actor_id); + if (traffic_light_it != _traffic_lights.end()) { + traffic_light_it->second._traffic_light_publisher->disable_for_ros(); + } +} + +bool UeWorldPublisher::is_enabled_for_ros(carla::streaming::detail::actor_id_type actor_id) const { + if ( actor_id == _actor_name_definition->id ) { + // the world publisher itself always enabled + return true; + } + auto vehicle_it = _vehicles.find(actor_id); + if (vehicle_it != _vehicles.end()) { + return vehicle_it->second._vehicle_publisher->is_enabled_for_ros(); + } + auto walker_it = _walkers.find(actor_id); + if (walker_it != _walkers.end()) { + return walker_it->second._walker_publisher->is_enabled_for_ros(); + } + auto traffic_sign_it = _traffic_signs.find(actor_id); + if (traffic_sign_it != _traffic_signs.end()) { + return traffic_sign_it->second._traffic_sign_publisher->is_enabled_for_ros(); + } + auto traffic_light_it = _traffic_lights.find(actor_id); + if (traffic_light_it != _traffic_lights.end()) { + return traffic_light_it->second._traffic_light_publisher->is_enabled_for_ros(); + } + return false; +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/UeWorldPublisher.h b/LibCarla/source/carla/ros2/publishers/UeWorldPublisher.h new file mode 100644 index 00000000000..96ba1d53060 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeWorldPublisher.h @@ -0,0 +1,216 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/ROS2NameRegistry.h" +#include "carla/ros2/publishers/CarlaActorListPublisher.h" +#include "carla/ros2/publishers/CarlaStatusPublisher.h" +#include "carla/ros2/publishers/ClockPublisher.h" +#include "carla/ros2/publishers/MapPublisher.h" +#include "carla/ros2/publishers/ObjectsPublisher.h" +#include "carla/ros2/publishers/ObjectsWithCovariancePublisher.h" +#include "carla/ros2/publishers/TrafficLightPublisher.h" +#include "carla/ros2/publishers/TrafficLightsPublisher.h" +#include "carla/ros2/publishers/TrafficSignPublisher.h" +#include "carla/ros2/publishers/UePublisherBaseSensor.h" +#include "carla/ros2/publishers/VehiclePublisher.h" +#include "carla/ros2/publishers/WalkerPublisher.h" +#include "carla/ros2/subscribers/AckermannControlSubscriber.h" +#include "carla/ros2/subscribers/ActorSetTransformSubscriber.h" +#include "carla/ros2/subscribers/CarlaControlSubscriber.h" +#include "carla/ros2/subscribers/CarlaSynchronizationWindowSubscriber.h" +#include "carla/ros2/subscribers/VehicleControlSubscriber.h" +#include "carla/ros2/subscribers/WalkerControlSubscriber.h" +#include "carla/ros2/types/Object.h" +#include "carla/ros2/types/VehicleActorDefinition.h" +#include "carla/rpc/RpcServerInterface.h" +#include "carla/sensor/data/ActorDynamicState.h" +#include "carla/sensor/s11n/EpisodeStateSerializer.h" + +namespace carla { +namespace ros2 { + +/** + * The publisher collecting all world related publishing activities that are not explicitly defined as + * The publisher collecting all world related publishing activities that are not explicitly defined as + * - clock + * - transform + * - sensor + * - vehicle + * - traffic_light + * - traffic_sign + * + */ +class UeWorldPublisher : public UePublisherBaseSensor { +public: + UeWorldPublisher(carla::rpc::RpcServerInterface &carla_server, std::shared_ptr name_registry, + std::shared_ptr sensor_actor_definition); + virtual ~UeWorldPublisher() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + + /** + * Implement PublisherInterface::SubscribersConnected() interface + */ + bool SubscribersConnected() const override { + return true; + } + + /** + * Process incoming messages + */ + void ProcessMessages(); + + /** + * Implement actions on actors removed + */ + void RemoveActor(ActorId actor); + + /** + * Implement UePublisherBaseSensor::UpdateSensorData() + */ + void UpdateSensorData(std::shared_ptr sensor_header, + carla::SharedBufferView buffer_view) override; + /** + * Implement UePublisherBaseSensor::UpdateSensorDataPostAction() + */ + void UpdateSensorDataPostAction() override; + + + void AddVehicleUe(std::shared_ptr vehicle_actor_definition, + carla::ros2::types::VehicleControlCallback vehicle_control_callback, + carla::ros2::types::VehicleAckermannControlCallback vehicle_ackermann_control_callback, + carla::ros2::types::ActorSetTransformCallback vehicle_set_transform_callback); + void AddWalkerUe(std::shared_ptr walker_actor_definition, + carla::ros2::types::WalkerControlCallback walker_control_callback); + void AddTrafficLightUe( + std::shared_ptr traffic_light_actor_definition); + void AddTrafficSignUe(std::shared_ptr traffic_sign_actor_definition); + + uint64_t CurrentFrame() const { + return _frame; + } + carla::ros2::types::Timestamp const &CurrentTimestamp() const { + return _timestamp; + } + + auto GetTransformPublisher() const { + return _transform_publisher; + } + + /* + * @brief enable actor ROS publication + */ + void enable_for_ros(carla::streaming::detail::actor_id_type actor_id) override; + + /* + * @brief disable actor ROS publication + */ + void disable_for_ros(carla::streaming::detail::actor_id_type actor_id) override; + + /* + * @brief is the actor publisher actually enabled for ROS publication + */ + bool is_enabled_for_ros(carla::streaming::detail::actor_id_type actor_id) const override; + +private: + void UpdateAndPublishStatus(); + + using EpisodeHeaderConst = carla::sensor::s11n::EpisodeStateSerializer::Header const; + + /** + * @brief provides access to the image header stored at the start of the buffer + */ + std::shared_ptr header_view(const carla::SharedBufferView buffer_view) { + return std::shared_ptr(buffer_view, + reinterpret_cast(buffer_view.get()->data())); + } + + /** + * @brief access the buffer data as vector + */ + std::vector> + buffer_data_2_vector(const carla::SharedBufferView buffer_view) const { + return carla::sensor::data::buffer_data_accessed_by_vector( + buffer_view, carla::sensor::s11n::EpisodeStateSerializer::header_offset); + } + + carla::ros2::types::Timestamp _timestamp{}; + uint64_t _frame{0u}; + carla::sensor::s11n::EpisodeStateSerializer::Header _episode_header; + bool _frame_changed{false}; + // ensure to send out at least one message with empty object list + bool _objects_changed{true}; + std::unordered_map> _objects; + + struct UeVehicle { + explicit UeVehicle(std::shared_ptr carla_vehicle_publisher) + : _vehicle_publisher(carla_vehicle_publisher) {} + std::shared_ptr _vehicle_publisher; + std::shared_ptr _vehicle_controller; + std::shared_ptr _vehicle_ackermann_controller; + std::shared_ptr _actor_set_transform_subscriber; + + void Init(std::shared_ptr domain_participant); + }; + std::unordered_map _vehicles; + + struct UeWalker { + explicit UeWalker(std::shared_ptr carla_walker_publisher) + : _walker_publisher(carla_walker_publisher) {} + std::shared_ptr _walker_publisher; + std::shared_ptr _walker_controller; + carla::ros2::types::WalkerControlCallback _walker_control_callback; + void Init(std::shared_ptr domain_participant); + }; + std::unordered_map _walkers; + + struct UeTrafficLight { + explicit UeTrafficLight(std::shared_ptr carla_traffic_light_publisher) + : _traffic_light_publisher(carla_traffic_light_publisher) {} + std::shared_ptr _traffic_light_publisher; + + void Init(std::shared_ptr domain_participant); + }; + std::unordered_map _traffic_lights; + + struct UeTrafficSign { + explicit UeTrafficSign(std::shared_ptr carla_traffic_sign_publisher) + : _traffic_sign_publisher(carla_traffic_sign_publisher) {} + std::shared_ptr _traffic_sign_publisher; + + void Init(std::shared_ptr domain_participant); + }; + std::unordered_map _traffic_signs; + + std::shared_ptr _domain_participant_impl; + + carla::rpc::RpcServerInterface &_carla_server; + std::shared_ptr _name_registry; + // publisher + std::shared_ptr _carla_status_publisher; + std::shared_ptr _carla_actor_list_publisher; + std::shared_ptr _clock_publisher; + std::shared_ptr _map_publisher; + std::shared_ptr _objects_publisher; + std::shared_ptr _objects_with_covariance_publisher; + std::shared_ptr _traffic_lights_publisher; + // subscriber + std::shared_ptr _carla_control_subscriber; + std::shared_ptr _sync_subscriber; + + bool _initialized{false}; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/VehiclePublisher.cpp b/LibCarla/source/carla/ros2/publishers/VehiclePublisher.cpp new file mode 100644 index 00000000000..19676ed3e29 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/VehiclePublisher.cpp @@ -0,0 +1,157 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "VehiclePublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" +#include "carla/ros2/types/Speed.h" +#include "carla/ros2/types/VehicleAckermannControl.h" +#include "carla/ros2/types/VehicleControl.h" + +namespace carla { +namespace ros2 { + +VehiclePublisher::VehiclePublisher(std::shared_ptr vehicle_actor_definition, + std::shared_ptr transform_publisher, + std::shared_ptr objects_publisher, + std::shared_ptr objects_with_covariance_publisher) + : PublisherBaseTransform(std::static_pointer_cast(vehicle_actor_definition), + transform_publisher), + _vehicle_info_publisher(std::make_shared()), + _vehicle_control_status_publisher(std::make_shared()), + _vehicle_odometry_publisher(std::make_shared()), + _vehicle_speed_publisher(std::make_shared()), + _vehicle_telemetry_publisher(std::make_shared()), + _vehicle_object_publisher(std::make_shared(*this, objects_publisher)), + _vehicle_object_with_covariance_publisher(std::make_shared(*this, objects_with_covariance_publisher)) { + // prefill some vehicle info data + _vehicle_info_publisher->Message().id(vehicle_actor_definition->id); + _vehicle_info_publisher->Message().type(vehicle_actor_definition->type_id); + _vehicle_info_publisher->Message().rolename(vehicle_actor_definition->role_name); + _vehicle_info_publisher->Message().shape().type(shape_msgs::msg::SolidPrimitive_Constants::BOX); + auto const ros_extent = vehicle_actor_definition->bounding_box.extent * 2.f; + _vehicle_info_publisher->Message().shape().dimensions({ros_extent.x, ros_extent.y, ros_extent.z}); + _vehicle_info_publisher->Message().shape().polygon().points(*vehicle_actor_definition->vertex_polygon.polygon()); + for (auto wheel : vehicle_actor_definition->vehicle_physics_control.GetWheels()) { + auto wheel_info = carla_msgs::msg::CarlaVehicleInfoWheel(); + wheel_info.tire_friction(wheel.tire_friction); + wheel_info.damping_rate(wheel.damping_rate); + wheel_info.max_steer_angle(carla::geom::Math::ToRadians(wheel.max_steer_angle)); + wheel_info.radius(wheel.radius); + wheel_info.max_brake_torque(wheel.max_brake_torque); + wheel_info.max_handbrake_torque(wheel.max_handbrake_torque); + + auto wheel_position = wheel.position; + // TODO: do we have to divide here by 100? (such was in ros brigde, but to my undertanding and search in the source + // code, it might be already correct. If not, then better to switch type of wheel_position from Vector3D to Location + // to have automatic cm -> m conversion object->Transform().GetTransform().InverseTransformPoint(wheel_position); + wheel_info.position(CoordinateSystemTransform::TransformLocationToVector3Msg(wheel_position)); + _vehicle_info_publisher->Message().wheels().push_back(wheel_info); + } + _vehicle_info_publisher->Message().max_rpm(vehicle_actor_definition->vehicle_physics_control.max_rpm); + _vehicle_info_publisher->Message().moi(vehicle_actor_definition->vehicle_physics_control.moi); + _vehicle_info_publisher->Message().damping_rate_full_throttle( + vehicle_actor_definition->vehicle_physics_control.damping_rate_full_throttle); + _vehicle_info_publisher->Message().damping_rate_zero_throttle_clutch_engaged( + vehicle_actor_definition->vehicle_physics_control.damping_rate_zero_throttle_clutch_engaged); + _vehicle_info_publisher->Message().damping_rate_zero_throttle_clutch_disengaged( + vehicle_actor_definition->vehicle_physics_control.damping_rate_zero_throttle_clutch_disengaged); + _vehicle_info_publisher->Message().use_gear_autobox(vehicle_actor_definition->vehicle_physics_control.use_gear_autobox); + _vehicle_info_publisher->Message().gear_switch_time(vehicle_actor_definition->vehicle_physics_control.gear_switch_time); + _vehicle_info_publisher->Message().clutch_strength(vehicle_actor_definition->vehicle_physics_control.clutch_strength); + _vehicle_info_publisher->Message().mass(vehicle_actor_definition->vehicle_physics_control.mass); + _vehicle_info_publisher->Message().drag_coefficient(vehicle_actor_definition->vehicle_physics_control.drag_coefficient); + _vehicle_info_publisher->Message().center_of_mass(CoordinateSystemTransform::TransformLocationToVector3Msg( + vehicle_actor_definition->vehicle_physics_control.center_of_mass)); + _vehicle_info_publisher->SetMessageUpdated(); +} + +bool VehiclePublisher::Init(std::shared_ptr domain_participant) { + return _vehicle_info_publisher->Init(domain_participant, get_topic_name("vehicle_info"), PublisherBase::get_topic_qos()) && + _vehicle_control_status_publisher->Init(domain_participant, get_topic_name("vehicle_control_status"), get_topic_qos()) && + _vehicle_odometry_publisher->Init(domain_participant, get_topic_name("odometry"), get_topic_qos()) && + _vehicle_speed_publisher->Init(domain_participant, get_topic_name("speed"), get_topic_qos()) && + _vehicle_telemetry_publisher->Init(domain_participant, get_topic_name("vehicle_telemetry"), get_topic_qos()) && + _vehicle_object_publisher->Init(domain_participant) && + _vehicle_object_with_covariance_publisher->Init(domain_participant); +} + +bool VehiclePublisher::Publish() { + if (!_vehicle_info_published) { + _vehicle_info_published = _vehicle_info_publisher->Publish(); + } + bool success = _vehicle_info_published; + success &= _vehicle_control_status_publisher->Publish(); + success &= _vehicle_odometry_publisher->Publish(); + success &= _vehicle_speed_publisher->Publish(); + success &= _vehicle_telemetry_publisher->Publish(); + success &= _vehicle_object_publisher->Publish(); + success &= _vehicle_object_with_covariance_publisher->Publish(); + return success; +} + +bool VehiclePublisher::SubscribersConnected() const { + return _vehicle_info_publisher->SubscribersConnected() || _vehicle_control_status_publisher->SubscribersConnected() || + _vehicle_odometry_publisher->SubscribersConnected() || _vehicle_speed_publisher->SubscribersConnected() || + _vehicle_telemetry_publisher->SubscribersConnected() || + _vehicle_object_publisher->SubscribersConnected() || + _vehicle_object_with_covariance_publisher->SubscribersConnected(); +} + +void VehiclePublisher::UpdateVehicle(std::shared_ptr &object, + carla::sensor::data::ActorDynamicState const &actor_dynamic_state, + carla::rpc::RpcServerInterface &carla_server) { + _vehicle_odometry_publisher->SetMessageHeader(object->Timestamp().time(), "map"); + _vehicle_odometry_publisher->Message().child_frame_id(frame_id()); + _vehicle_odometry_publisher->Message().pose(object->Transform().pose_with_covariance()); + _vehicle_odometry_publisher->Message().twist(object->AcceleratedMovement().twist_with_covariance()); + + _vehicle_speed_publisher->Message().data(object->Speed().speed().data()); + + auto response = carla_server.call_get_telemetry_data(_actor_name_definition->id); + if (!response) { + carla::log_warning("VehiclePublisher: Failed to get telemetry data for actor id ", + std::to_string(_actor_name_definition->id), ": ", response.GetError().What()); + } + else { + auto telemetry_data = response.Get(); + _vehicle_telemetry_publisher->SetMessageHeader(object->Timestamp().time(), "map"); + _vehicle_telemetry_publisher->Message().throttle(telemetry_data.throttle); + _vehicle_telemetry_publisher->Message().steer(telemetry_data.steer); + _vehicle_telemetry_publisher->Message().brake(telemetry_data.brake); + _vehicle_telemetry_publisher->Message().engine_rpm(telemetry_data.engine_rpm); + _vehicle_telemetry_publisher->Message().gear(telemetry_data.gear); + _vehicle_telemetry_publisher->Message().drag(telemetry_data.drag); + _vehicle_telemetry_publisher->Message().wheels().clear(); + for (auto const &wheel: telemetry_data.wheels) { + carla_msgs::msg::CarlaVehicleTelemetryDataWheel wheel_msg; + wheel_msg.tire_friction(wheel.tire_friction); + wheel_msg.lat_slip(wheel.lat_slip); + wheel_msg.long_slip(wheel.long_slip); + wheel_msg.omega(wheel.omega); + wheel_msg.tire_load(wheel.tire_load); + wheel_msg.normalized_tire_load(wheel.normalized_tire_load); + wheel_msg.torque(wheel.torque); + wheel_msg.long_force(wheel.long_force); + wheel_msg.lat_force(wheel.lat_force); + wheel_msg.normalized_long_force(wheel.normalized_long_force); + wheel_msg.normalized_lat_force(wheel.normalized_lat_force); + _vehicle_telemetry_publisher->Message().wheels().push_back(wheel_msg); + } + } + + _vehicle_control_status_publisher->Message().active_control_type(carla::ros2::types::GetVehicleControlType(actor_dynamic_state)); + _vehicle_control_status_publisher->Message().last_applied_vehicle_control( + carla::ros2::types::VehicleControl(actor_dynamic_state.state.vehicle_data.GetVehicleControl()) + .carla_vehicle_control()); + _vehicle_control_status_publisher->Message().last_applied_ackermann_control( + carla::ros2::types::VehicleAckermannControl(actor_dynamic_state.state.vehicle_data.GetAckermannControl()) + .carla_vehicle_ackermann_control()); + + _vehicle_object_publisher->UpdateObject(object); + _vehicle_object_with_covariance_publisher->UpdateObject(object); +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/VehiclePublisher.h b/LibCarla/source/carla/ros2/publishers/VehiclePublisher.h new file mode 100644 index 00000000000..45af8acf1c8 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/VehiclePublisher.h @@ -0,0 +1,74 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/ObjectPublisher.h" +#include "carla/ros2/publishers/ObjectWithCovariancePublisher.h" +#include "carla/ros2/publishers/PublisherBaseTransform.h" +#include "carla/ros2/types/Object.h" +#include "carla/ros2/types/Transform.h" +#include "carla/ros2/types/VehicleActorDefinition.h" +#include "carla/rpc/VehiclePhysicsControl.h" +#include "carla/rpc/RpcServerInterface.h" +#include "carla/sensor/data/ActorDynamicState.h" +#include "carla_msgs/msg/CarlaVehicleControlStatusPubSubTypes.h" +#include "carla_msgs/msg/CarlaVehicleInfoPubSubTypes.h" +#include "carla_msgs/msg/CarlaVehicleTelemetryDataPubSubTypes.h" +#include "nav_msgs/msg/OdometryPubSubTypes.h" +#include "std_msgs/msg/Float32PubSubTypes.h" + +namespace carla { +namespace ros2 { + +using VehicleInfoPublisherImpl = + DdsPublisherImpl; +using VehicleControlStatusPublisherImpl = + DdsPublisherImpl; +using VehicleSpeedPublisherImpl = + DdsPublisherImpl; +using VehicleOdometryPublisherImpl = + DdsPublisherImpl; +using VehicleTelemetryDataPublisherImpl = + DdsPublisherImpl; + + +class VehiclePublisher : public PublisherBaseTransform { +public: + VehiclePublisher(std::shared_ptr vehicle_actor_definition, + std::shared_ptr transform_publisher, + std::shared_ptr objects_publisher, + std::shared_ptr objects_with_covariance_publisher); + virtual ~VehiclePublisher() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + void UpdateVehicle(std::shared_ptr &object, + carla::sensor::data::ActorDynamicState const &actor_dynamic_state, + carla::rpc::RpcServerInterface &carla_server); + +private: + std::shared_ptr _vehicle_info_publisher; + bool _vehicle_info_published{false}; + std::shared_ptr _vehicle_control_status_publisher; + std::shared_ptr _vehicle_odometry_publisher; + std::shared_ptr _vehicle_speed_publisher; + std::shared_ptr _vehicle_telemetry_publisher; + std::shared_ptr _vehicle_object_publisher; + std::shared_ptr _vehicle_object_with_covariance_publisher; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/WalkerPublisher.cpp b/LibCarla/source/carla/ros2/publishers/WalkerPublisher.cpp new file mode 100644 index 00000000000..cebf5d3c9c7 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/WalkerPublisher.cpp @@ -0,0 +1,45 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "WalkerPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" +#include "carla/ros2/types/Speed.h" +#include "carla/ros2/types/WalkerControl.h" + +namespace carla { +namespace ros2 { + +WalkerPublisher::WalkerPublisher(std::shared_ptr walker_actor_definition, + std::shared_ptr transform_publisher, + std::shared_ptr objects_publisher, + std::shared_ptr objects_with_covariance_publisher) + : PublisherBaseTransform(std::static_pointer_cast(walker_actor_definition), + transform_publisher), + _walker_object_publisher(std::make_shared(*this, objects_publisher)), + _walker_object_with_covariance_publisher(std::make_shared(*this, objects_with_covariance_publisher)) {} + +bool WalkerPublisher::Init(std::shared_ptr domain_participant) { + return _walker_object_publisher->Init(domain_participant) && + _walker_object_with_covariance_publisher->Init(domain_participant); +} + +bool WalkerPublisher::Publish() { + return _walker_object_publisher->Publish() && + _walker_object_with_covariance_publisher->Publish(); +} + +bool WalkerPublisher::SubscribersConnected() const { + return _walker_object_publisher->SubscribersConnected() || + _walker_object_with_covariance_publisher->SubscribersConnected(); +} + +void WalkerPublisher::UpdateWalker(std::shared_ptr &object, + carla::sensor::data::ActorDynamicState const &) { + _walker_object_publisher->UpdateObject(object); + _walker_object_with_covariance_publisher->UpdateObject(object); +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/WalkerPublisher.h b/LibCarla/source/carla/ros2/publishers/WalkerPublisher.h new file mode 100644 index 00000000000..8e90fee2f28 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/WalkerPublisher.h @@ -0,0 +1,48 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/publishers/ObjectPublisher.h" +#include "carla/ros2/publishers/ObjectWithCovariancePublisher.h" +#include "carla/ros2/publishers/PublisherBaseTransform.h" +#include "carla/ros2/types/Object.h" +#include "carla/ros2/types/Transform.h" +#include "carla/ros2/types/WalkerActorDefinition.h" +#include "carla/sensor/data/ActorDynamicState.h" + +namespace carla { +namespace ros2 { + +class WalkerPublisher : public PublisherBaseTransform { +public: + WalkerPublisher(std::shared_ptr walker_actor_definition, + std::shared_ptr transform_publisher, + std::shared_ptr objects_publisher, + std::shared_ptr objects_with_covariance_publisher); + virtual ~WalkerPublisher() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + /** + * Implement PublisherInterface::SubscribersConnected interface + */ + bool SubscribersConnected() const override; + + void UpdateWalker(std::shared_ptr &object, + carla::sensor::data::ActorDynamicState const &actor_dynamic_state); + +private: + std::shared_ptr _walker_object_publisher; + std::shared_ptr _walker_object_with_covariance_publisher; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/services/DestroyObjectService.cpp b/LibCarla/source/carla/ros2/services/DestroyObjectService.cpp new file mode 100644 index 00000000000..aa5ef289ada --- /dev/null +++ b/LibCarla/source/carla/ros2/services/DestroyObjectService.cpp @@ -0,0 +1,34 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/ros2/services/DestroyObjectService.h" + +#include "carla/ros2/impl/DdsServiceImpl.h" + +namespace carla { +namespace ros2 { + +DestroyObjectService::DestroyObjectService( + carla::rpc::RpcServerInterface &carla_server, + std::shared_ptr actor_name_definition) + : ServiceBase(carla_server, actor_name_definition), _impl(std::make_shared()) {} + +bool DestroyObjectService::Init(std::shared_ptr domain_participant) { + _impl->SetServiceCallback(std::bind(&DestroyObjectService::DestroyObject, this, std::placeholders::_1)); + return _impl->Init(domain_participant, get_topic_name()); +} + +void DestroyObjectService::CheckRequest() { + _impl->CheckRequest(); +} + +carla_msgs::srv::DestroyObject_Response DestroyObjectService::DestroyObject( + carla_msgs::srv::DestroyObject_Request const &request) { + carla_msgs::srv::DestroyObject_Response response; + response.success(_carla_server.call_destroy_actor(carla::streaming::detail::actor_id_type(request.id()))); + return response; +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/services/DestroyObjectService.h b/LibCarla/source/carla/ros2/services/DestroyObjectService.h new file mode 100644 index 00000000000..7d330be144a --- /dev/null +++ b/LibCarla/source/carla/ros2/services/DestroyObjectService.h @@ -0,0 +1,43 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +#include "carla/ros2/services/ServiceBase.h" +#include "carla_msgs/srv/DestroyObjectPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using DestroyObjectServiceImpl = + DdsServiceImpl; + +class DestroyObjectService + : public ServiceBase { +public: + DestroyObjectService(carla::rpc::RpcServerInterface &carla_server, + std::shared_ptr actor_name_definition); + virtual ~DestroyObjectService() = default; + + /** + * Implements ServiceInterface::CheckRequest() interface + */ + void CheckRequest() override; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + +private: + carla_msgs::srv::DestroyObject_Response DestroyObject(carla_msgs::srv::DestroyObject_Request const &request); + + std::shared_ptr _impl; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/services/GetAvailableMapsService.cpp b/LibCarla/source/carla/ros2/services/GetAvailableMapsService.cpp new file mode 100644 index 00000000000..390f655eba2 --- /dev/null +++ b/LibCarla/source/carla/ros2/services/GetAvailableMapsService.cpp @@ -0,0 +1,40 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/ros2/services/GetAvailableMapsService.h" + +#include + +#include "carla/actors/BlueprintLibrary.h" +#include "carla/ros2/impl/DdsServiceImpl.h" + +namespace carla { +namespace ros2 { + +GetAvailableMapsService::GetAvailableMapsService( + carla::rpc::RpcServerInterface &carla_server, + std::shared_ptr actor_name_definition) + : ServiceBase(carla_server, actor_name_definition), _impl(std::make_shared()) {} + +bool GetAvailableMapsService::Init(std::shared_ptr domain_participant) { + _impl->SetServiceCallback(std::bind(&GetAvailableMapsService::GetAvailableMaps, this, std::placeholders::_1)); + return _impl->Init(domain_participant, get_topic_name()); +} + +void GetAvailableMapsService::CheckRequest() { + _impl->CheckRequest(); +} + +carla_msgs::srv::GetAvailableMaps_Response GetAvailableMapsService::GetAvailableMaps( + carla_msgs::srv::GetAvailableMaps_Request const &request) { + carla_msgs::srv::GetAvailableMaps_Response response; + + for ( auto const &map_name: _carla_server.call_get_available_maps().Get()) { + response.maps().push_back(map_name); + } + return response; +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/services/GetAvailableMapsService.h b/LibCarla/source/carla/ros2/services/GetAvailableMapsService.h new file mode 100644 index 00000000000..430fd1c1792 --- /dev/null +++ b/LibCarla/source/carla/ros2/services/GetAvailableMapsService.h @@ -0,0 +1,43 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +#include "carla/ros2/services/ServiceBase.h" +#include "carla_msgs/srv/GetAvailableMapsPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using GetAvailableMapsServiceImpl = + DdsServiceImpl; + +class GetAvailableMapsService + : public ServiceBase { +public: + GetAvailableMapsService(carla::rpc::RpcServerInterface &carla_server, + std::shared_ptr actor_name_definition); + virtual ~GetAvailableMapsService() = default; + + /** + * Implements ServiceInterface::CheckRequest() interface + */ + void CheckRequest() override; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + +private: + carla_msgs::srv::GetAvailableMaps_Response GetAvailableMaps(carla_msgs::srv::GetAvailableMaps_Request const &request); + + std::shared_ptr _impl; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/services/GetBlueprintsService.cpp b/LibCarla/source/carla/ros2/services/GetBlueprintsService.cpp new file mode 100644 index 00000000000..f2a0d529817 --- /dev/null +++ b/LibCarla/source/carla/ros2/services/GetBlueprintsService.cpp @@ -0,0 +1,57 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/ros2/services/GetBlueprintsService.h" + +#include + +#include "carla/actors/BlueprintLibrary.h" +#include "carla/ros2/impl/DdsServiceImpl.h" + +namespace carla { +namespace ros2 { + +GetBlueprintsService::GetBlueprintsService( + carla::rpc::RpcServerInterface &carla_server, + std::shared_ptr actor_name_definition) + : ServiceBase(carla_server, actor_name_definition), _impl(std::make_shared()) {} + +bool GetBlueprintsService::Init(std::shared_ptr domain_participant) { + _impl->SetServiceCallback(std::bind(&GetBlueprintsService::GetBlueprints, this, std::placeholders::_1)); + return _impl->Init(domain_participant, get_topic_name()); +} + +void GetBlueprintsService::CheckRequest() { + _impl->CheckRequest(); +} + +carla_msgs::srv::GetBlueprints_Response GetBlueprintsService::GetBlueprints( + carla_msgs::srv::GetBlueprints_Request const &request) { + carla_msgs::srv::GetBlueprints_Response response; + + auto filter = request.filter(); + if (filter == "") { + filter = "*"; + } + auto blueprints = carla::actors::BlueprintLibrary(_carla_server.call_get_actor_definitions().Get()).Filter(filter); + response.blueprints().reserve(blueprints->size()); + for (auto const &blueprint : *blueprints) { + carla_msgs::msg::CarlaActorBlueprint ros_blueprint; + ros_blueprint.id(blueprint.GetId()); + for (auto const &tag: blueprint.GetTags()) { + ros_blueprint.tags().push_back(tag); + } + for (auto const &attribute: blueprint) { + diagnostic_msgs::msg::KeyValue key_value; + key_value.key(attribute.GetId()); + key_value.value(attribute.GetValue()); + ros_blueprint.attributes().push_back(key_value); + } + response.blueprints().push_back(ros_blueprint); + } + return response; +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/services/GetBlueprintsService.h b/LibCarla/source/carla/ros2/services/GetBlueprintsService.h new file mode 100644 index 00000000000..0a3e968b5a1 --- /dev/null +++ b/LibCarla/source/carla/ros2/services/GetBlueprintsService.h @@ -0,0 +1,43 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +#include "carla/ros2/services/ServiceBase.h" +#include "carla_msgs/srv/GetBlueprintsPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using GetBlueprintsServiceImpl = + DdsServiceImpl; + +class GetBlueprintsService + : public ServiceBase { +public: + GetBlueprintsService(carla::rpc::RpcServerInterface &carla_server, + std::shared_ptr actor_name_definition); + virtual ~GetBlueprintsService() = default; + + /** + * Implements ServiceInterface::CheckRequest() interface + */ + void CheckRequest() override; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + +private: + carla_msgs::srv::GetBlueprints_Response GetBlueprints(carla_msgs::srv::GetBlueprints_Request const &request); + + std::shared_ptr _impl; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/services/LoadMapService.cpp b/LibCarla/source/carla/ros2/services/LoadMapService.cpp new file mode 100644 index 00000000000..e6575a3770a --- /dev/null +++ b/LibCarla/source/carla/ros2/services/LoadMapService.cpp @@ -0,0 +1,78 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/ros2/services/LoadMapService.h" + +#include + +#include "carla/actors/BlueprintLibrary.h" +#include "carla/ros2/impl/DdsServiceImpl.h" + +namespace carla { +namespace ros2 { + +LoadMapService::LoadMapService( + carla::rpc::RpcServerInterface &carla_server, + std::shared_ptr actor_name_definition) + : ServiceBase(carla_server, actor_name_definition), _impl(std::make_shared()) { +} + +bool LoadMapService::Init(std::shared_ptr domain_participant) { + _impl->SetServiceCallback(std::bind(&LoadMapService::LoadMap, this, std::placeholders::_1)); + return _impl->Init(domain_participant, get_topic_name()); +} + +void LoadMapService::CheckRequest() { + _impl->CheckRequest(); +} + +carla_msgs::srv::LoadMap_Response LoadMapService::LoadMap( + carla_msgs::srv::LoadMap_Request const &request) { + carla_msgs::srv::LoadMap_Response response; + + auto new_map_name = request.mapname(); + auto current_map_name = _carla_server.call_get_map_info().Get().name; + std::string map_name_prefix = "Carla/Maps/"; + std::string map_name_without_prefix = request.mapname(); + if (map_name_without_prefix.find(map_name_prefix) == 0) { + map_name_without_prefix.erase(0, map_name_prefix.length()); + } + std::string map_name_with_prefix = map_name_prefix + map_name_without_prefix; + std::string error_reason; + if( request.force_reload() || + (!(map_name_without_prefix == current_map_name) && !(map_name_with_prefix == current_map_name))) { + auto call_response = _carla_server.call_load_new_episode(map_name_without_prefix, request.reset_episode_settings(), static_cast(request.map_layers())); + if ( call_response.HasError() ) { + response.success(false); + error_reason = call_response.GetError().What(); + } + else { + response.success(true); + } + } + else { + response.success(false); + error_reason = "Map already loaded and no reload requested"; + } + if (response.success()) { + log_warning("ROS2:LoadMapService(", request.mapname(), + "): request to load new episode '", map_name_without_prefix, + "' with force: ", request.force_reload()?"True":"False", + ", reset_episode_settings: ", request.reset_episode_settings()?"True":"False", + " and map_layers: ", request.map_layers(), + " succeeded"); + } + else { + log_error("ROS2:LoadMapService(", request.mapname(), + "): request to load new episode '", map_name_without_prefix, + "' with force: ", request.force_reload()?"True":"False", + ", reset_episode_settings: ", request.reset_episode_settings()?"True":"False", + " and map_layers: ", request.map_layers(), + " failed: ", error_reason); + } + return response; +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/services/LoadMapService.h b/LibCarla/source/carla/ros2/services/LoadMapService.h new file mode 100644 index 00000000000..82b8dd44a59 --- /dev/null +++ b/LibCarla/source/carla/ros2/services/LoadMapService.h @@ -0,0 +1,43 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +#include "carla/ros2/services/ServiceBase.h" +#include "carla_msgs/srv/LoadMapPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using LoadMapServiceImpl = + DdsServiceImpl; + +class LoadMapService + : public ServiceBase { +public: + LoadMapService(carla::rpc::RpcServerInterface &carla_server, + std::shared_ptr actor_name_definition); + virtual ~LoadMapService() = default; + + /** + * Implements ServiceInterface::CheckRequest() interface + */ + void CheckRequest() override; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + +private: + carla_msgs::srv::LoadMap_Response LoadMap(carla_msgs::srv::LoadMap_Request const &request); + + std::shared_ptr _impl; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/services/ServiceBase.h b/LibCarla/source/carla/ros2/services/ServiceBase.h new file mode 100644 index 00000000000..d61ebacc844 --- /dev/null +++ b/LibCarla/source/carla/ros2/services/ServiceBase.h @@ -0,0 +1,41 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +#include "carla/ros2/ROS2NameRecord.h" +#include "carla/ros2/ROS2QoS.h" +#include "carla/ros2/services/ServiceInterface.h" +#include "carla/rpc/RpcServerInterface.h" + +namespace carla { +namespace ros2 { + +/** + A Service base class. + */ +template +class DdsServiceImpl; + +template +class ServiceBase : public ServiceInterface, public ROS2NameRecord { +public: + ServiceBase(carla::rpc::RpcServerInterface &carla_server, + std::shared_ptr actor_name_definition) + : ROS2NameRecord(actor_name_definition), _carla_server(carla_server) {} + virtual ~ServiceBase() = default; + + /** + * Initialze the service + */ + virtual bool Init(std::shared_ptr domain_participant) = 0; + +protected: + carla::rpc::RpcServerInterface &_carla_server; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/services/ServiceInterface.h b/LibCarla/source/carla/ros2/services/ServiceInterface.h new file mode 100644 index 00000000000..76fa4cc6682 --- /dev/null +++ b/LibCarla/source/carla/ros2/services/ServiceInterface.h @@ -0,0 +1,44 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +namespace carla { +namespace ros2 { + +class ServiceInterface { +public: + /** + * Default constructor. + */ + ServiceInterface() = default; + /** + * Copy operation not allowed due to active subscriptions + */ + ServiceInterface(const ServiceInterface&) = delete; + /** + * Assignment operation not allowed due to active subscriptions + */ + ServiceInterface& operator=(const ServiceInterface&) = delete; + /** + * Move operation not allowed due to active subscriptions + */ + ServiceInterface(ServiceInterface&&) = delete; + /** + * Move operation not allowed due to active subscriptions + */ + ServiceInterface& operator=(ServiceInterface&&) = delete; + + /** + * Default destructor. + */ + virtual ~ServiceInterface() = default; + + /** + * Check if there is a new request available and execute callback if required + */ + virtual void CheckRequest() = 0; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/services/SetEpisodeSettingsService.cpp b/LibCarla/source/carla/ros2/services/SetEpisodeSettingsService.cpp new file mode 100644 index 00000000000..9e75a433e77 --- /dev/null +++ b/LibCarla/source/carla/ros2/services/SetEpisodeSettingsService.cpp @@ -0,0 +1,44 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/ros2/services/SetEpisodeSettingsService.h" + +#include "carla/ros2/impl/DdsServiceImpl.h" +#include "carla/ros2/types/EpisodeSettings.h" + +namespace carla { +namespace ros2 { + +SetEpisodeSettingsService::SetEpisodeSettingsService( + carla::rpc::RpcServerInterface &carla_server, + std::shared_ptr actor_name_definition) + : ServiceBase(carla_server, actor_name_definition), _impl(std::make_shared()) {} + +bool SetEpisodeSettingsService::Init(std::shared_ptr domain_participant) { + _impl->SetServiceCallback(std::bind(&SetEpisodeSettingsService::SetEpisodeSettings, this, std::placeholders::_1)); + return _impl->Init(domain_participant, get_topic_name()); +} + +void SetEpisodeSettingsService::CheckRequest() { + _impl->CheckRequest(); +} + +carla_msgs::srv::SetEpisodeSettings_Response SetEpisodeSettingsService::SetEpisodeSettings( + carla_msgs::srv::SetEpisodeSettings_Request const &request) { + + carla_msgs::srv::SetEpisodeSettings_Response response; + carla::ros2::types::EpisodeSettings episode_settings(request.episode_settings()); + auto result = _carla_server.call_set_episode_settings(episode_settings.GetEpisodeSettings()); + if ( result > 0 ) { + response.success(true); + } + else { + response.success(false); + } + + return response; +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/services/SetEpisodeSettingsService.h b/LibCarla/source/carla/ros2/services/SetEpisodeSettingsService.h new file mode 100644 index 00000000000..d942acccdbc --- /dev/null +++ b/LibCarla/source/carla/ros2/services/SetEpisodeSettingsService.h @@ -0,0 +1,43 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +#include "carla/ros2/services/ServiceBase.h" +#include "carla_msgs/srv/SetEpisodeSettingsPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using SetEpisodeSettingsServiceImpl = + DdsServiceImpl; + +class SetEpisodeSettingsService + : public ServiceBase { +public: + SetEpisodeSettingsService(carla::rpc::RpcServerInterface &carla_server, + std::shared_ptr actor_name_definition); + virtual ~SetEpisodeSettingsService() = default; + + /** + * Implements ServiceInterface::CheckRequest() interface + */ + void CheckRequest() override; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + +private: + carla_msgs::srv::SetEpisodeSettings_Response SetEpisodeSettings(carla_msgs::srv::SetEpisodeSettings_Request const &request); + + std::shared_ptr _impl; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/services/SpawnObjectService.cpp b/LibCarla/source/carla/ros2/services/SpawnObjectService.cpp new file mode 100644 index 00000000000..fc406824b8f --- /dev/null +++ b/LibCarla/source/carla/ros2/services/SpawnObjectService.cpp @@ -0,0 +1,123 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/ros2/services/SpawnObjectService.h" + +#include +#include + +#include "carla/actors/BlueprintLibrary.h" +#include "carla/ros2/impl/DdsServiceImpl.h" +#include "carla/ros2/types/Transform.h" + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 +#include +#include +#include "Carla/Server/CarlaServer.h" +#endif + +namespace carla { +namespace ros2 { + +SpawnObjectService::SpawnObjectService(carla::rpc::RpcServerInterface &carla_server, + std::shared_ptr actor_name_definition) + : ServiceBase(carla_server, actor_name_definition), _impl(std::make_shared()) {} + +bool SpawnObjectService::Init(std::shared_ptr domain_participant) { + _impl->SetServiceCallback(std::bind(&SpawnObjectService::SpawnObject, this, std::placeholders::_1)); + return _impl->Init(domain_participant, get_topic_name()); +} + +void SpawnObjectService::CheckRequest() { + _impl->CheckRequest(); +} + +carla_msgs::srv::SpawnObject_Response SpawnObjectService::SpawnObject( + carla_msgs::srv::SpawnObject_Request const &request) { + carla_msgs::srv::SpawnObject_Response response; + + log_warning("ROS2:SpawnObjectService processing request for '", request.blueprint().id(), "' Pose: ", request.random_pose()?"random":"provided"); + + int32_t retry_count = 5; + do { + carla::geom::Transform transform; + if (request.random_pose()) { + std::vector spawn_points; + auto map_info = _carla_server.call_get_map_info(); + std::vector result; + std::sample(map_info.Get().recommended_spawn_points.begin(), map_info.Get().recommended_spawn_points.end(), + std::back_inserter(result), 1, std::mt19937{std::random_device{}()}); + if (result.empty()) { + log_error("ROS2:SpawnObjectService failed to retrieve random spawn point"); + response.error_string("SpawnObjectService: failed to retrieve random spawn point"); + response.id(-1); + return response; + } + transform = *result.begin(); + } else { + // no retry if spawn position is explicitly provided + retry_count = 0u; + carla::ros2::types::Transform ros_transform(request.transform()); + transform = ros_transform.GetTransform(); + } + log_warning("ROS2:SpawnObjectService processing request. Pose: (", transform.location.x, ", ", transform.location.y, ", ", transform.location.z, ")"); + auto blueprints = + carla::actors::BlueprintLibrary(_carla_server.call_get_actor_definitions().Get()).Filter(request.blueprint().id()); + if (blueprints->empty()) { + log_error("ROS2:SpawnObjectService failed to retrieve any matching blueprint", request.blueprint().id()); + response.error_string("SpawnObjectService: failed to retrieve matching blueprint"); + response.id(-1); + return response; + } else { + std::vector blueprint_result; + std::sample(blueprints->begin(), blueprints->end(), std::back_inserter(blueprint_result), 1, + std::mt19937{std::random_device{}()}); + if (blueprint_result.size() == 0) { + log_error("ROS2:SpawnObjectService failed to retrieve random matching blueprint", request.blueprint().id()); + response.error_string("SpawnObjectService: failed to retrieve random matching blueprint"); + response.id(-1); + return response; + } + auto blueprint = *blueprint_result.begin(); + for (auto const &attribute : request.blueprint().attributes()) { + blueprint.SetAttribute(attribute.key(), attribute.value()); + } + + auto actor_description = blueprint.MakeActorDescription(); + + carla::rpc::ActorAttributeValue attribute_value; + attribute_value.id = "enabled_for_ros"; + attribute_value.type = carla::rpc::ActorAttributeType::Bool; + attribute_value.value = "true"; + actor_description.attributes.push_back(attribute_value); + + carla::rpc::Response result; + carla::streaming::detail::actor_id_type const parent = request.attach_to(); + if (parent == 0) { + result = _carla_server.call_spawn_actor(actor_description, transform); + } else { + result = _carla_server.call_spawn_actor_with_parent(actor_description, transform, parent, + carla::rpc::AttachmentType::Rigid, ""); + } + if (result.HasError()) { + if ( retry_count > 0 ) { + retry_count--; + } + else { + response.id(-1); + response.error_string(result.GetError().What()); + log_warning("ROS2:SpawnObjectService spawn failed: ", result.GetError().What()); + return response; + } + } else { + response.id(int32_t(result.Get().id)); + log_warning("ROS2:SpawnObjectService spawn succeeded: ", int32_t(result.Get().id)); + return response; + } + } + }while(retry_count > 0); +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/services/SpawnObjectService.h b/LibCarla/source/carla/ros2/services/SpawnObjectService.h new file mode 100644 index 00000000000..82766a78c1b --- /dev/null +++ b/LibCarla/source/carla/ros2/services/SpawnObjectService.h @@ -0,0 +1,43 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +#include "carla/ros2/services/ServiceBase.h" +#include "carla_msgs/srv/SpawnObjectPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using SpawnObjectServiceImpl = + DdsServiceImpl; + +class SpawnObjectService + : public ServiceBase { +public: + SpawnObjectService(carla::rpc::RpcServerInterface &carla_server, + std::shared_ptr actor_name_definition); + virtual ~SpawnObjectService() = default; + + /** + * Implements ServiceInterface::CheckRequest() interface + */ + void CheckRequest() override; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + +private: + carla_msgs::srv::SpawnObject_Response SpawnObject(carla_msgs::srv::SpawnObject_Request const &request); + + std::shared_ptr _impl; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/AckermannControlSubscriber.cpp b/LibCarla/source/carla/ros2/subscribers/AckermannControlSubscriber.cpp index 5a670c14a60..f98ec259fc4 100644 --- a/LibCarla/source/carla/ros2/subscribers/AckermannControlSubscriber.cpp +++ b/LibCarla/source/carla/ros2/subscribers/AckermannControlSubscriber.cpp @@ -1,28 +1,29 @@ -#include "AckermannControlSubscriber.h" +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . -#include "carla/ros2/ROS2CallbackData.h" +#include "carla/ros2/subscribers/AckermannControlSubscriber.h" + +#include "carla/ros2/impl/DdsSubscriberImpl.h" namespace carla { namespace ros2 { - ROS2CallbackData AckermannControlSubscriber::GetMessage() { - auto message = _impl->GetMessage(); +AckermannControlSubscriber::AckermannControlSubscriber( + ROS2NameRecord& parent, carla::ros2::types::VehicleAckermannControlCallback vehicle_ackermann_control_callback) + : SubscriberBase(parent), + _impl(std::make_shared(*this)), + _vehicle_ackermann_control_callback(vehicle_ackermann_control_callback) {} - AckermannControl control; - control.steer = message.drive().steering_angle(); - control.steer_speed = message.drive().steering_angle_velocity(); - control.speed = message.drive().speed(); - control.acceleration = message.drive().acceleration(); - control.jerk = message.drive().jerk(); - return control; - } +bool AckermannControlSubscriber::Init(std::shared_ptr domain_participant) { + return _impl->Init(domain_participant, get_topic_name("control/vehicle_ackermann_drive_cmd"), get_topic_qos()); +} - void AckermannControlSubscriber::ProcessMessages(ActorCallback callback) { - if (_impl->HasNewMessage()) { - auto control = this->GetMessage(); - callback(this->GetActor(), control); - } +void AckermannControlSubscriber::ProcessMessages() { + while (_impl->HasPublishersConnected() && _impl->HasNewMessage()) { + _vehicle_ackermann_control_callback(carla::ros2::types::VehicleAckermannControl(_impl->GetMessage())); } +} } // namespace ros2 } // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/AckermannControlSubscriber.h b/LibCarla/source/carla/ros2/subscribers/AckermannControlSubscriber.h index 36749b4c098..29909c72cde 100644 --- a/LibCarla/source/carla/ros2/subscribers/AckermannControlSubscriber.h +++ b/LibCarla/source/carla/ros2/subscribers/AckermannControlSubscriber.h @@ -1,42 +1,42 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). // This work is licensed under the terms of the MIT license. // For a copy, see . #pragma once #include +#include -#include "BaseSubscriber.h" -#include "SubscriberImpl.h" - -#include "carla/ros2/types/AckermannDriveStamped.h" -#include "carla/ros2/types/AckermannDriveStampedPubSubTypes.h" - -#include "carla/ros2/ROS2CallbackData.h" +#include "ackermann_msgs/msg/AckermannDriveStampedPubSubTypes.h" +#include "carla/ros2/subscribers/SubscriberBase.h" +#include "carla/ros2/types/VehicleActorDefinition.h" namespace carla { namespace ros2 { - class AckermannControlSubscriber : public BaseSubscriber { - public: - struct AckermannMsgTraits { - using msg_type = ackermann_msgs::msg::AckermannDriveStamped; - using msg_pubsub_type = ackermann_msgs::msg::AckermannDriveStampedPubSubType; - }; - - - AckermannControlSubscriber(void* vehicle, std::string base_topic_name, std::string frame_id) : - BaseSubscriber(vehicle, base_topic_name, frame_id), - _impl(std::make_shared>()) { - _impl->Init(this->GetBaseTopicName() + "/ackermann_control_cmd"); - } - - ROS2CallbackData GetMessage(); - void ProcessMessages(ActorCallback callback); - - private: - std::shared_ptr> _impl; - }; +using AckermannControlSubscriberImpl = + DdsSubscriberImpl; + +class AckermannControlSubscriber : public SubscriberBase { +public: + explicit AckermannControlSubscriber( + ROS2NameRecord& parent, carla::ros2::types::VehicleAckermannControlCallback vehicle_ackermann_control_callback); + virtual ~AckermannControlSubscriber() = default; + + /** + * Implements SubscriberBase::ProcessMessages() + */ + void ProcessMessages() override; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + +private: + std::shared_ptr _impl; + carla::ros2::types::VehicleAckermannControlCallback _vehicle_ackermann_control_callback; +}; } // namespace ros2 } // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/ActorSetTransformSubscriber.cpp b/LibCarla/source/carla/ros2/subscribers/ActorSetTransformSubscriber.cpp new file mode 100644 index 00000000000..10162a8b723 --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/ActorSetTransformSubscriber.cpp @@ -0,0 +1,29 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/ros2/subscribers/ActorSetTransformSubscriber.h" + +#include "carla/ros2/impl/DdsSubscriberImpl.h" + +namespace carla { +namespace ros2 { + +ActorSetTransformSubscriber::ActorSetTransformSubscriber(ROS2NameRecord& parent, + carla::ros2::types::ActorSetTransformCallback actor_set_transform_callback) + : SubscriberBase(parent), + _impl(std::make_shared(*this)), + _actor_set_transform_callback(actor_set_transform_callback) {} + +bool ActorSetTransformSubscriber::Init(std::shared_ptr domain_participant) { + return _impl->Init(domain_participant, get_topic_name("control/set_transform"), get_topic_qos()); +} + +void ActorSetTransformSubscriber::ProcessMessages() { + while (_impl->HasPublishersConnected() && _impl->HasNewMessage()) { + _actor_set_transform_callback(carla::ros2::types::Transform(_impl->GetMessage())); + } +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/ActorSetTransformSubscriber.h b/LibCarla/source/carla/ros2/subscribers/ActorSetTransformSubscriber.h new file mode 100644 index 00000000000..94940cad8f0 --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/ActorSetTransformSubscriber.h @@ -0,0 +1,41 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +#include "carla/ros2/subscribers/SubscriberBase.h" +#include "carla/ros2/types/ActorDefinition.h" +#include "geometry_msgs/msg/PosePubSubTypes.h" + +namespace carla { +namespace ros2 { + +using ActorSetTransformSubscriberImpl = + DdsSubscriberImpl; + +class ActorSetTransformSubscriber : public SubscriberBase { +public: + explicit ActorSetTransformSubscriber(ROS2NameRecord& parent, + carla::ros2::types::ActorSetTransformCallback actor_set_transform_callback); + virtual ~ActorSetTransformSubscriber() = default; + + /** + * Implements SubscriberBase::ProcessMessages() + */ + void ProcessMessages() override; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + +private: + std::shared_ptr _impl; + carla::ros2::types::ActorSetTransformCallback _actor_set_transform_callback; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/BaseSubscriber.h b/LibCarla/source/carla/ros2/subscribers/BaseSubscriber.h deleted file mode 100644 index 0a8f1b72aca..00000000000 --- a/LibCarla/source/carla/ros2/subscribers/BaseSubscriber.h +++ /dev/null @@ -1,49 +0,0 @@ -// Copyright (c) 2025Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include -#include - -#include "carla/ros2/ROS2CallbackData.h" - - -namespace carla { -namespace ros2 { - - class BaseSubscriber { - public: - - BaseSubscriber() {} - - BaseSubscriber(std::string base_topic_name) : - _base_topic_name(base_topic_name) {} - - BaseSubscriber(std::string base_topic_name, std::string frame_id) : - _base_topic_name(base_topic_name), - _frame_id(frame_id) {} - - BaseSubscriber(void* actor, std::string base_topic_name, std::string frame_id) : - _actor(actor), - _base_topic_name(base_topic_name), - _frame_id(frame_id) {} - - const std::string GetBaseTopicName() {return _base_topic_name; } - const std::string GetFrameId() { return _frame_id; } - - virtual ROS2CallbackData GetMessage() = 0; - virtual void ProcessMessages(ActorCallback callback) = 0; - - void* GetActor() { return _actor; } - - protected: - std::string _frame_id = ""; - std::string _base_topic_name = ""; - - void* _actor { nullptr }; - }; - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/CarlaControlSubscriber.cpp b/LibCarla/source/carla/ros2/subscribers/CarlaControlSubscriber.cpp new file mode 100644 index 00000000000..4eafc582f31 --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/CarlaControlSubscriber.cpp @@ -0,0 +1,46 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/ros2/subscribers/CarlaControlSubscriber.h" + +#include "carla/ros2/impl/DdsSubscriberImpl.h" + +namespace carla { +namespace ros2 { + +CarlaControlSubscriber::CarlaControlSubscriber(ROS2NameRecord &parent, carla::rpc::RpcServerInterface &carla_server) + : SubscriberBaseSynchronizationClient(parent, carla_server), _impl(std::make_shared(*this)) {} + +bool CarlaControlSubscriber::Init(std::shared_ptr domain_participant) { + return _impl->Init(domain_participant, get_topic_name("control/carla_control"), get_topic_qos().reliable()); +} + +CarlaControlSubscriber::~CarlaControlSubscriber() { +} + +void CarlaControlSubscriber::ProcessMessages() { + while (_impl->HasPublishersConnected() && _impl->HasNewMessage()) { + + auto const carla_control_msg_entry = _impl->GetMessageEntry(); + auto const command = carla_control_msg_entry.message.command(); + auto const synchronization_participant = GetSynchronizationParticipant(carla_control_msg_entry.publisher); + carla::log_debug("CarlaControlSubscriber[", ThisAsSynchronizationClient(), + "]::ProcessMessages(", carla_control_msg_entry.publisher, ", ", + synchronization_participant, + ") command =", std::to_string(command)); + switch (command) { + case carla_msgs::msg::CarlaControl_Constants::PLAY: + _carla_server.call_update_synchronization_window(ThisAsSynchronizationClient(), + synchronization_participant); + break; + case carla_msgs::msg::CarlaControl_Constants::PAUSE: + case carla_msgs::msg::CarlaControl_Constants::STEP_ONCE: + _carla_server.call_tick(ThisAsSynchronizationClient(), synchronization_participant); + break; + } + } +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/CarlaControlSubscriber.h b/LibCarla/source/carla/ros2/subscribers/CarlaControlSubscriber.h new file mode 100644 index 00000000000..ffffe871f3d --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/CarlaControlSubscriber.h @@ -0,0 +1,46 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +#include "carla/ros2/subscribers/SubscriberBaseSynchronizationClient.h" +#include "carla/rpc/RpcServerInterface.h" +#include "carla_msgs/msg/CarlaControlPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using CarlaControlSubscriberImpl = + DdsSubscriberImpl; + +class CarlaControlSubscriber : public SubscriberBaseSynchronizationClient { +public: + explicit CarlaControlSubscriber(ROS2NameRecord &parent, carla::rpc::RpcServerInterface &carla_server); + virtual ~CarlaControlSubscriber(); + + /** + * Implements SubscriberBase::ProcessMessages() + */ + void ProcessMessages() override; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + +private: + /** + * Implements SubscriberBaseSynchronizationClient::ThisAsSynchronizationClient() interface + */ + carla::rpc::synchronization_client_id_type ThisAsSynchronizationClient() override { + return get_topic_name("control/carla_control"); + } + + std::shared_ptr _impl; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/CarlaEgoVehicleControlSubscriber.cpp b/LibCarla/source/carla/ros2/subscribers/CarlaEgoVehicleControlSubscriber.cpp deleted file mode 100644 index d3d3e7b646b..00000000000 --- a/LibCarla/source/carla/ros2/subscribers/CarlaEgoVehicleControlSubscriber.cpp +++ /dev/null @@ -1,30 +0,0 @@ -#include "CarlaEgoVehicleControlSubscriber.h" - -#include "carla/ros2/ROS2CallbackData.h" - -namespace carla { -namespace ros2 { - - ROS2CallbackData CarlaEgoVehicleControlSubscriber::GetMessage() { - auto message = _impl->GetMessage(); - - VehicleControl control; - control.throttle = message.throttle(); - control.steer = message.steer(); - control.brake = message.brake(); - control.hand_brake = message.hand_brake(); - control.reverse = message.reverse(); - control.gear = message.gear(); - control.manual_gear_shift = message.manual_gear_shift(); - return control; - } - - void CarlaEgoVehicleControlSubscriber::ProcessMessages(ActorCallback callback) { - if (_impl->HasNewMessage()) { - auto control = this->GetMessage(); - callback(this->GetActor(), control); - } - } - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/CarlaEgoVehicleControlSubscriber.h b/LibCarla/source/carla/ros2/subscribers/CarlaEgoVehicleControlSubscriber.h deleted file mode 100644 index 39f108fb30d..00000000000 --- a/LibCarla/source/carla/ros2/subscribers/CarlaEgoVehicleControlSubscriber.h +++ /dev/null @@ -1,42 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include - -#include "BaseSubscriber.h" -#include "SubscriberImpl.h" - -#include "carla/ros2/types/CarlaEgoVehicleControl.h" -#include "carla/ros2/types/CarlaEgoVehicleControlPubSubTypes.h" - -#include "carla/ros2/ROS2CallbackData.h" - -namespace carla { -namespace ros2 { - - class CarlaEgoVehicleControlSubscriber : public BaseSubscriber { - public: - struct ControlMsgTraits { - using msg_type = carla_msgs::msg::CarlaEgoVehicleControl; - using msg_pubsub_type = carla_msgs::msg::CarlaEgoVehicleControlPubSubType; - }; - - - CarlaEgoVehicleControlSubscriber(void* vehicle, std::string base_topic_name, std::string frame_id) : - BaseSubscriber(vehicle, base_topic_name, frame_id), - _impl(std::make_shared>()) { - _impl->Init(this->GetBaseTopicName() + "/vehicle_control_cmd"); - } - - ROS2CallbackData GetMessage(); - void ProcessMessages(ActorCallback callback); - - private: - std::shared_ptr> _impl; - }; - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/CarlaSynchronizationWindowSubscriber.cpp b/LibCarla/source/carla/ros2/subscribers/CarlaSynchronizationWindowSubscriber.cpp new file mode 100644 index 00000000000..d99188f10ec --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/CarlaSynchronizationWindowSubscriber.cpp @@ -0,0 +1,44 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/ros2/subscribers/CarlaSynchronizationWindowSubscriber.h" + +#include "carla/ros2/impl/DdsSubscriberImpl.h" + +namespace carla { +namespace ros2 { + +CarlaSynchronizationWindowSubscriber::CarlaSynchronizationWindowSubscriber(ROS2NameRecord &parent, + carla::rpc::RpcServerInterface &carla_server) + : SubscriberBaseSynchronizationClient(parent, carla_server), + _impl(std::make_shared(*this)) + {} + +bool CarlaSynchronizationWindowSubscriber::Init(std::shared_ptr domain_participant) { + return _impl->Init(domain_participant, get_topic_name("control/synchronization_window"), get_topic_qos().reliable()); +} + +CarlaSynchronizationWindowSubscriber::~CarlaSynchronizationWindowSubscriber() { +} + +void CarlaSynchronizationWindowSubscriber::ProcessMessages() { + while (_impl->HasPublishersConnected() && _impl->HasNewMessage()) { + auto const carla_synchronization_window_msg_entry = _impl->GetMessageEntry(); + auto carla_synchronization_target_game_time = + carla_synchronization_window_msg_entry.message.synchronization_window_target_game_time(); + auto const synchronization_participant = GetSynchronizationParticipant(carla_synchronization_window_msg_entry.publisher); + + carla::log_debug("CarlaSynchronizationWindowSubscriber[", ThisAsSynchronizationClient(), + "]::ProcessMessages(", carla_synchronization_window_msg_entry.publisher, ", ", + synchronization_participant, + ")=", carla_synchronization_target_game_time); + _carla_server.call_update_synchronization_window( + ThisAsSynchronizationClient(), + synchronization_participant, + carla_synchronization_target_game_time); + } +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/CarlaSynchronizationWindowSubscriber.h b/LibCarla/source/carla/ros2/subscribers/CarlaSynchronizationWindowSubscriber.h new file mode 100644 index 00000000000..f79117308f2 --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/CarlaSynchronizationWindowSubscriber.h @@ -0,0 +1,49 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +#include "carla/ros2/subscribers/SubscriberBaseSynchronizationClient.h" +#include "carla/rpc/RpcServerInterface.h" +#include "carla/rpc/ServerSynchronizationTypes.h" +#include "carla_msgs/msg/CarlaSynchronizationWindowPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using CarlaSynchronizationWindowSubscriberImpl = + DdsSubscriberImpl; + +class CarlaSynchronizationWindowSubscriber : public SubscriberBaseSynchronizationClient { +public: + explicit CarlaSynchronizationWindowSubscriber(ROS2NameRecord &parent, carla::rpc::RpcServerInterface &carla_server); + virtual ~CarlaSynchronizationWindowSubscriber(); + + /** + * Implements SubscriberBase::ProcessMessages() + */ + void ProcessMessages() override; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + +private: + + /** + * Implements SubscriberBaseSynchronizationClient::ThisAsSynchronizationClient() interface + */ + carla::rpc::synchronization_client_id_type ThisAsSynchronizationClient() override { + return get_topic_name("control/synchronization_window"); + } + + std::shared_ptr _impl; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/SubscriberBase.h b/LibCarla/source/carla/ros2/subscribers/SubscriberBase.h new file mode 100644 index 00000000000..24353232962 --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/SubscriberBase.h @@ -0,0 +1,80 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +#include "carla/ros2/ROS2NameRecord.h" +#include "carla/ros2/ROS2QoS.h" + +namespace carla { +namespace ros2 { + +/** + A Subscriber base class. + */ +template +class DdsSubscriberImpl; + +/** + * Subscriber Base class + */ +template +class SubscriberBase { +public: + SubscriberBase(ROS2NameRecord &parent) : _parent(parent) {} + virtual ~SubscriberBase() = default; + + /** + * Initialze the subscriber + */ + virtual bool Init(std::shared_ptr domain_participant) = 0; + + /** + * Process all available messages. + */ + virtual void ProcessMessages() = 0; + + /** + * A new publisher has connected to this subscriber. + */ + virtual void PublisherConnected(std::string const &publisher_guid) { + (void)publisher_guid; + } + + /** + * A publisher has disconnected from this subscriber. + */ + virtual void PublisherDisconnected(std::string const &publisher_guid) { + (void)publisher_guid; + } + + /* + * @brief Default get_topic_qos() for subscribers + * + * Be aware: The default selection for subscribers is NOT as done default in ROS2 (which aims compatibility to ROS1)! + * Per default, we want to achieve the most compatible combination within ROS2 world in the sense, + * that receiption is possible for all possible publisher configurations. + * https://docs.ros.org/en/humble/Concepts/Intermediate/About-Quality-of-Service-Settings.html#qos-compatibilities + * + * Reliability::BEST_EFFORT + * Durability::VOLATILE + * History::KEEP_LAST, depth: 10u + */ + ROS2QoS get_topic_qos() const { + return DEFAULT_SUBSCRIBER_QOS; + }; + + std::string get_topic_name(std::string postfix = "") const { + return _parent.get_topic_name(postfix); + } + + +protected: + ROS2NameRecord &_parent; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/SubscriberBaseSynchronizationClient.h b/LibCarla/source/carla/ros2/subscribers/SubscriberBaseSynchronizationClient.h new file mode 100644 index 00000000000..2a2e7f312b1 --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/SubscriberBaseSynchronizationClient.h @@ -0,0 +1,85 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +#include "carla/ros2/subscribers/SubscriberBase.h" +#include "carla/rpc/RpcServerInterface.h" +#include "carla/rpc/ServerSynchronizationTypes.h" + +namespace carla { +namespace ros2 { + + +template +class SubscriberBaseSynchronizationClient : public SubscriberBase { +public: + explicit SubscriberBaseSynchronizationClient(ROS2NameRecord &parent, carla::rpc::RpcServerInterface &carla_server) : + SubscriberBase(parent), + _carla_server(carla_server) { + } + + virtual ~SubscriberBaseSynchronizationClient() { + if ( !_synchronization_client_id.empty() ) { + for (auto [publisher_guid, participant] : _carla_synchronization_window_participants) { + carla::log_debug("~SubscriberBaseSynchronizationClient[", _synchronization_client_id, "]:: disconnect publisher (", + publisher_guid, ", ", participant, ")"); + _carla_server.call_deregister_synchronization_participant(_synchronization_client_id, participant); + } + } + _carla_synchronization_window_participants.clear(); + } + + /** + * Implements SubscriberBase::PublisherConnected() + */ + void PublisherConnected(std::string const &publisher_guid) override { + if ( _synchronization_client_id.empty() ) { + _synchronization_client_id = ThisAsSynchronizationClient(); + } + auto carla_synchronization_window_participant = _carla_server.call_register_synchronization_participant(ThisAsSynchronizationClient()).Get(); + _carla_synchronization_window_participants.insert({publisher_guid, carla_synchronization_window_participant}); + carla::log_debug("SubscriberBaseSynchronizationClient[", ThisAsSynchronizationClient(), "]::PublisherConnected(", + publisher_guid, ", ", carla_synchronization_window_participant, ")"); + } + + /** + * Implements SubscriberBase::PublisherDisconnected() + */ + void PublisherDisconnected(std::string const &publisher_guid) override { + auto carla_synchronization_window_participant = GetSynchronizationParticipant(publisher_guid); + carla::log_debug("SubscriberBaseSynchronizationClient[", ThisAsSynchronizationClient(), "]::PublisherDisconnected(", + publisher_guid, ", ", carla_synchronization_window_participant, ")"); + _carla_server.call_deregister_synchronization_participant(ThisAsSynchronizationClient(), + carla_synchronization_window_participant); + _carla_synchronization_window_participants.erase(publisher_guid); + } + + +protected: + + virtual carla::rpc::synchronization_client_id_type ThisAsSynchronizationClient() = 0; + + carla::rpc::synchronization_participant_id_type GetSynchronizationParticipant(std::string const &participant_guid) { + auto find_result = _carla_synchronization_window_participants.find(participant_guid); + if ( find_result != _carla_synchronization_window_participants.end() ) { + return find_result->second; + } + carla::log_error("SubscriberBaseSynchronizationClient[", ThisAsSynchronizationClient(), "]::GetSynchronizationParticipant(", + participant_guid, ") participant not found."); + return carla::rpc::ALL_PARTICIPANTS; + } + + carla::rpc::RpcServerInterface &_carla_server; + +private: + std::map + _carla_synchronization_window_participants; + carla::rpc::synchronization_client_id_type _synchronization_client_id; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/SubscriberImpl.h b/LibCarla/source/carla/ros2/subscribers/SubscriberImpl.h deleted file mode 100644 index 9baaadd84d9..00000000000 --- a/LibCarla/source/carla/ros2/subscribers/SubscriberImpl.h +++ /dev/null @@ -1,149 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include - -#include "carla/ros2/subscribers/BaseSubscriber.h" - -#include -#include -#include - -#include -#include - -#include -#include -#include -#include -#include -#include - -#include - -#include -#include - -#include "carla/Logging.h" - -namespace carla { -namespace ros2 { - - namespace efd = eprosima::fastdds::dds; - using erc = eprosima::fastrtps::types::ReturnCode_t; - - template - class SubscriberImpl : public eprosima::fastdds::dds::DataReaderListener { - public: - using msg_type = typename S::msg_type; - using msg_pubsub_type = typename S::msg_pubsub_type; - - efd::DomainParticipant* _participant { nullptr }; - efd::Subscriber* _subscriber { nullptr }; - efd::Topic* _topic { nullptr }; - efd::DataReader* _datareader { nullptr }; - efd::TypeSupport _type { new msg_pubsub_type() }; - - void on_subscription_matched(efd::DataReader* reader, const efd::SubscriptionMatchedStatus& info) override { - _alive = (info.total_count > 0) ? true : false; - } - - void on_data_available(efd::DataReader* reader) override { - efd::SampleInfo info; - msg_type message; - - eprosima::fastrtps::types::ReturnCode_t rcode = reader->take_next_sample(&_message, &info); - if (rcode == eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_OK) { - // TODO: Process messages directly. - _new_message = true; - } else { - log_error("SubscriberImpl::on_data_available (", this->GetTopicName(), ") failed with code:", rcode()); - } - } - - ~SubscriberImpl() { - if (_datareader) - _subscriber->delete_datareader(_datareader); - - if (_subscriber) - _participant->delete_subscriber(_subscriber); - - if (_topic) - _participant->delete_topic(_topic); - - if (_participant) - efd::DomainParticipantFactory::get_instance()->delete_participant(_participant); - } - - // bool Init(std::string topic_name, S *subscriber) { - bool Init(std::string topic_name) { - if (_type == nullptr) { - log_error("Invalid TypeSupport"); - return false; - } - - efd::DomainParticipantQos pqos = efd::PARTICIPANT_QOS_DEFAULT; - auto factory = efd::DomainParticipantFactory::get_instance(); - _participant = factory->create_participant(0, pqos); - if (_participant == nullptr) { - log_error("Failed to create DomainParticipant"); - return false; - } - _type.register_type(_participant); - - efd::SubscriberQos subqos = efd::SUBSCRIBER_QOS_DEFAULT; - _subscriber = _participant->create_subscriber(subqos, nullptr); - if (_subscriber == nullptr) { - log_error("Failed to create Subscriber"); - return false; - } - - efd::TopicQos tqos = efd::TOPIC_QOS_DEFAULT; - _topic = _participant->create_topic(topic_name, _type->getName(), tqos); - if (_topic == nullptr) { - log_error("Failed to create Topic"); - return false; - } - - efd::DataReaderQos rqos = efd::DATAREADER_QOS_DEFAULT; - efd::DataReaderListener* listener = (efd::DataReaderListener*)(this); - _datareader = _subscriber->create_datareader(_topic, rqos, listener); - if (_datareader == nullptr) { - log_error("Failed to create DataReader"); - return false; - } - - _topic_name = topic_name; - - // _subscriber = subscriber; - return true; - } - - std::string GetTopicName() { - return _topic_name; - } - - bool IsAlive() { - return _alive; - } - - msg_type GetMessage() { - _new_message = false; - return _message; - } - - bool HasNewMessage() { return _new_message; } - - private: - std::string _topic_name; - - bool _alive { false }; - bool _new_message { false }; - msg_type _message; - }; - -} // namespace ros2 -} // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/SubscriberImplBase.h b/LibCarla/source/carla/ros2/subscribers/SubscriberImplBase.h new file mode 100644 index 00000000000..2fa2a0bb68a --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/SubscriberImplBase.h @@ -0,0 +1,165 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +namespace carla { +namespace ros2 { + +template +class SubscriberBase; + +/** + * Base class for subscriber implementations + */ +template +class SubscriberImplBase { +public: + /** + * Default constructor. + */ + SubscriberImplBase(SubscriberBase &parent) : _parent(parent) {} + /** + * Copy operation not allowed due to active subscriptions + */ + SubscriberImplBase(const SubscriberImplBase &) = delete; + /** + * Assignment operation not allowed due to active subscriptions + */ + SubscriberImplBase &operator=(const SubscriberImplBase &) = delete; + /** + * Move operation not allowed due to active subscriptions + */ + SubscriberImplBase(SubscriberImplBase &&) = delete; + /** + * Move operation not allowed due to active subscriptions + */ + SubscriberImplBase &operator=(SubscriberImplBase &&) = delete; + + /** + * Default destructor. + */ + virtual ~SubscriberImplBase() = default; + + struct MessageEntry { + // a process local unique identification of the publisher that has sent the message + std::string publisher{}; + // the actual message + MESSAGE_TYPE message{}; + }; + + /** + * Get the list of currently alive publishers in the order of their appearance. + */ + std::list GetConnectedPublishers() const { + std::lock_guard access_lock(_access_mutex); + return _connected_publishers; + } + + /** + * Check if there are publishers connected to this + */ + bool HasPublishersConnected() const { + std::lock_guard access_lock(_access_mutex); + return !_connected_publishers.empty(); + } + + /** + * Report how many publishers are connected to this + */ + std::size_t NumberPublishersConnected() const { + std::lock_guard access_lock(_access_mutex); + return _connected_publishers.size(); + } + + /** + * Check if there is a new message available + */ + bool HasNewMessage() const { + std::lock_guard access_lock(_access_mutex); + return !_messages.empty(); + } + + /** + * Get the list of the current available message entry. + */ + std::list GetMessageEntries() { + std::lock_guard access_lock(_access_mutex); + std::list messages; + messages.swap(_messages); + return messages; + } + + /** + * Implements SubscriberImplBase::GetMessageEntry() interface + */ + MessageEntry GetMessageEntry() { + std::lock_guard access_lock(_access_mutex); + if (_messages.empty()) { + return MessageEntry(); + } + auto message = _messages.front(); + _messages.pop_front(); + return message; + } + + /** + * Get the next message. This is a conventient function for subscribers that don't care on the identification of the + * sender. + */ + const MESSAGE_TYPE GetMessage() { + return GetMessageEntry().message; + } + +protected: + void AddMessage(std::string const &publisher_guid, MESSAGE_TYPE &message) { + std::lock_guard access_lock(_access_mutex); + _messages.push_back({publisher_guid, message}); + carla::log_debug("SubscriberImplBase[", _parent.get_topic_name(), "]::AddMessage(", publisher_guid, + ") number of messages: ", _messages.size()); + } + + void AddPublisher(std::string const &publisher_guid) { + { + std::lock_guard access_lock(_access_mutex); + _connected_publishers.push_back(publisher_guid); + carla::log_debug("SubscriberImplBase[", _parent.get_topic_name(), "]::AddPublisher(", publisher_guid, + ") number of connected publisher: ", _connected_publishers.size()); + } + _parent.PublisherConnected(publisher_guid); + } + + void RemovePublisher(std::string const &publisher_guid) { + _parent.PublisherDisconnected(publisher_guid); + { + std::lock_guard access_lock(_access_mutex); + _connected_publishers.remove_if([publisher_guid](std::string const &element) -> bool { + return publisher_guid == element; + }); + carla::log_debug("SubscriberImplBase[", _parent.get_topic_name(), "]::RemovePublisher(", publisher_guid, + ") number of connected publisher: ", _connected_publishers.size()); + } + } + + void Clear() { + std::lock_guard access_lock(_access_mutex); + for (auto const &publisher_guid: _connected_publishers) { + _parent.PublisherDisconnected(publisher_guid); + } + _connected_publishers.clear(); + _messages.clear(); + } + +private: + // keep the data private to ensure access_mutex is hold while accessing + mutable std::mutex _access_mutex{}; + SubscriberBase &_parent; + std::list _connected_publishers; + std::list _messages; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/UeV2XCustomSubscriber.cpp b/LibCarla/source/carla/ros2/subscribers/UeV2XCustomSubscriber.cpp new file mode 100644 index 00000000000..fff4cab61d4 --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/UeV2XCustomSubscriber.cpp @@ -0,0 +1,35 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/ros2/subscribers/UeV2XCustomSubscriber.h" + +#include "carla/ros2/impl/DdsSubscriberImpl.h" + +namespace carla { +namespace ros2 { + +UeV2XCustomSubscriber::UeV2XCustomSubscriber(ROS2NameRecord& parent, + carla::ros2::types::V2XCustomSendCallback v2x_custom_send_callback) + : SubscriberBase(parent), + _impl(std::make_shared(*this)), + _v2x_custom_send_callback(v2x_custom_send_callback) {} + +bool UeV2XCustomSubscriber::Init(std::shared_ptr domain_participant) { + // need to ensure reliable v2x data receiption and allow larger data chuncks (up to 100byte * 1000 = 100 kB) + return _impl->Init(domain_participant, get_topic_name("send"), get_topic_qos().reliable().keep_last(1000)); +} + +void UeV2XCustomSubscriber::ProcessMessages() { + while (_impl->HasPublishersConnected() && _impl->HasNewMessage()) { + auto const message = _impl->GetMessage(); + carla::rpc::CustomV2XBytes data; + data.bytes = message.bytes(); + data.data_size = message.data_size(); + + _v2x_custom_send_callback(data); + } +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/UeV2XCustomSubscriber.h b/LibCarla/source/carla/ros2/subscribers/UeV2XCustomSubscriber.h new file mode 100644 index 00000000000..8b353570eae --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/UeV2XCustomSubscriber.h @@ -0,0 +1,41 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +#include "carla/ros2/subscribers/SubscriberBase.h" +#include "carla/ros2/types/SensorActorDefinition.h" +#include "carla_msgs/msg/CarlaV2XByteArrayPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using UeV2XCustomSubscriberImpl = + DdsSubscriberImpl; + +class UeV2XCustomSubscriber : public SubscriberBase { +public: + explicit UeV2XCustomSubscriber(ROS2NameRecord& parent, + carla::ros2::types::V2XCustomSendCallback v2x_custom_send_callback); + virtual ~UeV2XCustomSubscriber() = default; + + /** + * Implements SubscriberBase::ProcessMessages() + */ + void ProcessMessages() override; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + +private: + std::shared_ptr _impl; + carla::ros2::types::V2XCustomSendCallback _v2x_custom_send_callback; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/VehicleControlSubscriber.cpp b/LibCarla/source/carla/ros2/subscribers/VehicleControlSubscriber.cpp new file mode 100644 index 00000000000..2bc9bc46593 --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/VehicleControlSubscriber.cpp @@ -0,0 +1,29 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/ros2/subscribers/VehicleControlSubscriber.h" + +#include "carla/ros2/impl/DdsSubscriberImpl.h" + +namespace carla { +namespace ros2 { + +VehicleControlSubscriber::VehicleControlSubscriber(ROS2NameRecord& parent, + carla::ros2::types::VehicleControlCallback vehicle_control_callback) + : SubscriberBase(parent), + _impl(std::make_shared(*this)), + _vehicle_control_callback(vehicle_control_callback) {} + +bool VehicleControlSubscriber::Init(std::shared_ptr domain_participant) { + return _impl->Init(domain_participant, get_topic_name("control/vehicle_control_cmd"), get_topic_qos()); +} + +void VehicleControlSubscriber::ProcessMessages() { + while (_impl->HasPublishersConnected() && _impl->HasNewMessage()) { + _vehicle_control_callback(carla::ros2::types::VehicleControl(_impl->GetMessage())); + } +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/VehicleControlSubscriber.h b/LibCarla/source/carla/ros2/subscribers/VehicleControlSubscriber.h new file mode 100644 index 00000000000..f1bbaac4b2f --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/VehicleControlSubscriber.h @@ -0,0 +1,41 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +#include "carla/ros2/subscribers/SubscriberBase.h" +#include "carla/ros2/types/VehicleActorDefinition.h" +#include "carla_msgs/msg/CarlaVehicleControlPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using VehicleControlSubscriberImpl = + DdsSubscriberImpl; + +class VehicleControlSubscriber : public SubscriberBase { +public: + explicit VehicleControlSubscriber(ROS2NameRecord& parent, + carla::ros2::types::VehicleControlCallback vehicle_control_callback); + virtual ~VehicleControlSubscriber() = default; + + /** + * Implements SubscriberBase::ProcessMessages() + */ + void ProcessMessages() override; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + +private: + std::shared_ptr _impl; + carla::ros2::types::VehicleControlCallback _vehicle_control_callback; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/WalkerControlSubscriber.cpp b/LibCarla/source/carla/ros2/subscribers/WalkerControlSubscriber.cpp new file mode 100644 index 00000000000..63e498d856a --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/WalkerControlSubscriber.cpp @@ -0,0 +1,29 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/ros2/subscribers/WalkerControlSubscriber.h" + +#include "carla/ros2/impl/DdsSubscriberImpl.h" + +namespace carla { +namespace ros2 { + +WalkerControlSubscriber::WalkerControlSubscriber(ROS2NameRecord& parent, + carla::ros2::types::WalkerControlCallback walker_control_callback) + : SubscriberBase(parent), + _impl(std::make_shared(*this)), + _walker_control_callback(walker_control_callback) {} + +bool WalkerControlSubscriber::Init(std::shared_ptr domain_participant) { + return _impl->Init(domain_participant, get_topic_name("control/walker_control_cmd"), get_topic_qos()); +} + +void WalkerControlSubscriber::ProcessMessages() { + while (_impl->HasPublishersConnected() && _impl->HasNewMessage()) { + _walker_control_callback(carla::ros2::types::WalkerControl(_impl->GetMessage())); + } +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/WalkerControlSubscriber.h b/LibCarla/source/carla/ros2/subscribers/WalkerControlSubscriber.h new file mode 100644 index 00000000000..7d805a59d3e --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/WalkerControlSubscriber.h @@ -0,0 +1,41 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +#include "carla/ros2/subscribers/SubscriberBase.h" +#include "carla/ros2/types/WalkerActorDefinition.h" +#include "carla_msgs/msg/CarlaWalkerControlPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using WalkerControlSubscriberImpl = + DdsSubscriberImpl; + +class WalkerControlSubscriber : public SubscriberBase { +public: + explicit WalkerControlSubscriber(ROS2NameRecord& parent, + carla::ros2::types::WalkerControlCallback walker_control_callback); + virtual ~WalkerControlSubscriber() = default; + + /** + * Implements SubscriberBase::ProcessMessages() + */ + void ProcessMessages() override; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + +private: + std::shared_ptr _impl; + carla::ros2::types::WalkerControlCallback _walker_control_callback; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/types/AcceleratedMovement.h b/LibCarla/source/carla/ros2/types/AcceleratedMovement.h new file mode 100644 index 00000000000..8b70bc79090 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/AcceleratedMovement.h @@ -0,0 +1,109 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/Debug.h" +#include "carla/geom/Acceleration.h" +#include "carla/ros2/types/AngularVelocity.h" +#include "carla/ros2/types/Speed.h" +#include "carla/ros2/types/Timestamp.h" +#include "carla/ros2/types/Twist.h" +#include "geometry_msgs/msg/AccelWithCovariance.h" + +namespace carla { +namespace ros2 { +namespace types { + +/** + Track accelerations based on Speed upates + + Considers the conversion from left-handed system (unreal) to right-handed + system (ROS) +*/ +class AcceleratedMovement { +public: + AcceleratedMovement() = default; + ~AcceleratedMovement() = default; + AcceleratedMovement(const AcceleratedMovement&) = default; + AcceleratedMovement& operator=(const AcceleratedMovement&) = default; + AcceleratedMovement(AcceleratedMovement&&) = default; + AcceleratedMovement& operator=(AcceleratedMovement&&) = default; + + void UpdateSpeed(Speed const& speed, AngularVelocity const& angular_velocity, Timestamp const& timestamp) { + auto delta_seconds = timestamp.Stamp() - _last_timestamp.Stamp(); + if (delta_seconds > 1e-9) { + auto last_linear_velocity_ros = _last_speed.LinearVelocityROS(); + auto current_linear_velocity_ros = speed.LinearVelocityROS(); + auto current_linear_acceleration_ros = (current_linear_velocity_ros - last_linear_velocity_ros) / delta_seconds; + _ros_accel.linear().x(current_linear_acceleration_ros.x); + _ros_accel.linear().y(current_linear_acceleration_ros.y); + _ros_accel.linear().z(current_linear_acceleration_ros.z); + + auto last_angular_velocity_ros = _last_angular_velocity.AngularVelocityROS(); + auto current_angular_velocity_ros = angular_velocity.AngularVelocityROS(); + auto current_angular_acceleration_ros = + (current_angular_velocity_ros - last_angular_velocity_ros) / delta_seconds; + _ros_accel.angular().x(current_angular_acceleration_ros.x); + _ros_accel.angular().y(current_angular_acceleration_ros.y); + _ros_accel.angular().z(current_angular_acceleration_ros.z); + } + _last_speed = speed; + _last_angular_velocity = angular_velocity; + _last_timestamp = timestamp; + } + + /** + * The resulting ROS geometry_msgs::msg::Accel + */ + geometry_msgs::msg::Accel accel() const { + return _ros_accel; + } + + /** + * The resulting ROS geometry_msgs::msg::AccelWithCovariance + */ + geometry_msgs::msg::AccelWithCovariance accel_with_covariance() const { + geometry_msgs::msg::AccelWithCovariance _ros_accel_with_covariance; + _ros_accel_with_covariance.accel(_ros_accel); + return _ros_accel_with_covariance; + } + + /** + * The resulting ROS geometry_msgs::msg::Twist + */ + geometry_msgs::msg::Twist twist() const { + carla::ros2::types::Twist ros_twist(_last_speed, _last_angular_velocity); + return ros_twist.twist(); + } + + /** + * The resulting ROS geometry_msgs::msg::TwistWithCovariance + */ + geometry_msgs::msg::TwistWithCovariance twist_with_covariance() const { + carla::ros2::types::Twist ros_twist(_last_speed, _last_angular_velocity); + return ros_twist.twist_with_covariance(); + } + + carla::ros2::types::Speed const& Speed() const { + return _last_speed; + } + + carla::ros2::types::AngularVelocity const& AngularVelocity() const { + return _last_angular_velocity; + } + + carla::ros2::types::Timestamp const& Timestamp() const { + return _last_timestamp; + } + +private: + carla::ros2::types::Speed _last_speed{carla::geom::Vector3D(), carla::geom::Quaternion()}; + carla::ros2::types::AngularVelocity _last_angular_velocity{carla::geom::AngularVelocity()}; + carla::ros2::types::Timestamp _last_timestamp; + geometry_msgs::msg::Accel _ros_accel; +}; +} // namespace types +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/Acceleration.h b/LibCarla/source/carla/ros2/types/Acceleration.h new file mode 100644 index 00000000000..1b1d1170356 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/Acceleration.h @@ -0,0 +1,48 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/geom/Acceleration.h" +#include "carla/ros2/types/CoordinateSystemTransform.h" +#include "geometry_msgs/msg/Accel.h" + +namespace carla { +namespace ros2 { +namespace types { + +/** + Convert a carla (linear) acceleration to a ROS accel (linear part) + + Considers the conversion from left-handed system (unreal) to right-handed + system (ROS) +*/ +class Acceleration { +public: + /** + * carla_acceleration: the carla linear acceleration; this is not provided by UE4 + * therefore has to be deduced from the Velocity + */ + Acceleration(carla::geom::Acceleration const& carla_linear_acceleration = carla::geom::Acceleration()) { + _ros_accel.linear() = CoordinateSystemTransform::TransformLinearAxisMsg(carla_linear_acceleration); + } + ~Acceleration() = default; + Acceleration(const Acceleration&) = default; + Acceleration& operator=(const Acceleration&) = default; + Acceleration(Acceleration&&) = default; + Acceleration& operator=(Acceleration&&) = default; + + /** + * The resulting ROS geometry_msgs::msg::Accel + */ + geometry_msgs::msg::Accel accel() const { + return _ros_accel; + } + +private: + geometry_msgs::msg::Accel _ros_accel; +}; +} // namespace types +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/AckermannDrive.h b/LibCarla/source/carla/ros2/types/AckermannDrive.h deleted file mode 100644 index b7488e1b169..00000000000 --- a/LibCarla/source/carla/ros2/types/AckermannDrive.h +++ /dev/null @@ -1,294 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// 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. - -/*! - * @file AckermannDrive.h - * This header file contains the declaration of the described types in the IDL file. - * - * This file was generated by the tool gen. - */ - -#ifndef _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVE_H_ -#define _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVE_H_ - - -#include - -#include -#include -#include -#include -#include -#include - -#if defined(_WIN32) -#if defined(EPROSIMA_USER_DLL_EXPORT) -#define eProsima_user_DllExport __declspec( dllexport ) -#else -#define eProsima_user_DllExport -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define eProsima_user_DllExport -#endif // _WIN32 - -#if defined(_WIN32) -#if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(ACKERMANNDRIVE_SOURCE) -#define ACKERMANNDRIVE_DllAPI __declspec( dllexport ) -#else -#define ACKERMANNDRIVE_DllAPI __declspec( dllimport ) -#endif // ACKERMANNDRIVE_SOURCE -#else -#define ACKERMANNDRIVE_DllAPI -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define ACKERMANNDRIVE_DllAPI -#endif // _WIN32 - -namespace eprosima { -namespace fastcdr { -class Cdr; -} // namespace fastcdr -} // namespace eprosima - - -namespace ackermann_msgs { - namespace msg { - /*! - * @brief This class represents the structure AckermannDrive defined by the user in the IDL file. - * @ingroup AckermannDrive - */ - class AckermannDrive - { - public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport AckermannDrive(); - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~AckermannDrive(); - - /*! - * @brief Copy constructor. - * @param x Reference to the object ackermann_msgs::msg::AckermannDrive that will be copied. - */ - eProsima_user_DllExport AckermannDrive( - const AckermannDrive& x); - - /*! - * @brief Move constructor. - * @param x Reference to the object ackermann_msgs::msg::AckermannDrive that will be copied. - */ - eProsima_user_DllExport AckermannDrive( - AckermannDrive&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object ackermann_msgs::msg::AckermannDrive that will be copied. - */ - eProsima_user_DllExport AckermannDrive& operator =( - const AckermannDrive& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object ackermann_msgs::msg::AckermannDrive that will be copied. - */ - eProsima_user_DllExport AckermannDrive& operator =( - AckermannDrive&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x ackermann_msgs::msg::AckermannDrive object to compare. - */ - eProsima_user_DllExport bool operator ==( - const AckermannDrive& x) const; - - /*! - * @brief Comparison operator. - * @param x ackermann_msgs::msg::AckermannDrive object to compare. - */ - eProsima_user_DllExport bool operator !=( - const AckermannDrive& x) const; - - /*! - * @brief This function sets a value in member steering_angle - * @param _steering_angle New value for member steering_angle - */ - eProsima_user_DllExport void steering_angle( - float _steering_angle); - - /*! - * @brief This function returns the value of member steering_angle - * @return Value of member steering_angle - */ - eProsima_user_DllExport float steering_angle() const; - - /*! - * @brief This function returns a reference to member steering_angle - * @return Reference to member steering_angle - */ - eProsima_user_DllExport float& steering_angle(); - - /*! - * @brief This function sets a value in member steering_angle_velocity - * @param _steering_angle_velocity New value for member steering_angle_velocity - */ - eProsima_user_DllExport void steering_angle_velocity( - float _steering_angle_velocity); - - /*! - * @brief This function returns the value of member steering_angle_velocity - * @return Value of member steering_angle_velocity - */ - eProsima_user_DllExport float steering_angle_velocity() const; - - /*! - * @brief This function returns a reference to member steering_angle_velocity - * @return Reference to member steering_angle_velocity - */ - eProsima_user_DllExport float& steering_angle_velocity(); - - /*! - * @brief This function sets a value in member speed - * @param _speed New value for member speed - */ - eProsima_user_DllExport void speed( - float _speed); - - /*! - * @brief This function returns the value of member speed - * @return Value of member speed - */ - eProsima_user_DllExport float speed() const; - - /*! - * @brief This function returns a reference to member speed - * @return Reference to member speed - */ - eProsima_user_DllExport float& speed(); - - /*! - * @brief This function sets a value in member acceleration - * @param _acceleration New value for member acceleration - */ - eProsima_user_DllExport void acceleration( - float _acceleration); - - /*! - * @brief This function returns the value of member acceleration - * @return Value of member acceleration - */ - eProsima_user_DllExport float acceleration() const; - - /*! - * @brief This function returns a reference to member acceleration - * @return Reference to member acceleration - */ - eProsima_user_DllExport float& acceleration(); - - /*! - * @brief This function sets a value in member jerk - * @param _jerk New value for member jerk - */ - eProsima_user_DllExport void jerk( - float _jerk); - - /*! - * @brief This function returns the value of member jerk - * @return Value of member jerk - */ - eProsima_user_DllExport float jerk() const; - - /*! - * @brief This function returns a reference to member jerk - * @return Reference to member jerk - */ - eProsima_user_DllExport float& jerk(); - - - /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ - eProsima_user_DllExport static size_t getMaxCdrSerializedSize( - size_t current_alignment = 0); - - /*! - * @brief This function returns the serialized size of a data depending on the buffer alignment. - * @param data Data which is calculated its serialized size. - * @param current_alignment Buffer alignment. - * @return Serialized size. - */ - eProsima_user_DllExport static size_t getCdrSerializedSize( - const ackermann_msgs::msg::AckermannDrive& data, - size_t current_alignment = 0); - - - /*! - * @brief This function serializes an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& cdr) const; - - /*! - * @brief This function deserializes an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr); - - - - /*! - * @brief This function returns the maximum serialized size of the Key of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ - eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( - size_t current_alignment = 0); - - /*! - * @brief This function tells you if the Key has been defined for this type - */ - eProsima_user_DllExport static bool isKeyDefined(); - - /*! - * @brief This function serializes the key members of an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void serializeKey( - eprosima::fastcdr::Cdr& cdr) const; - - private: - - float m_steering_angle; - float m_steering_angle_velocity; - float m_speed; - float m_acceleration; - float m_jerk; - - }; - } // namespace msg -} // namespace ackermann_msgs - -#endif // _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVE_H_ - diff --git a/LibCarla/source/carla/ros2/types/AckermannDrivePubSubTypes.h b/LibCarla/source/carla/ros2/types/AckermannDrivePubSubTypes.h deleted file mode 100644 index d2db6e7cc6a..00000000000 --- a/LibCarla/source/carla/ros2/types/AckermannDrivePubSubTypes.h +++ /dev/null @@ -1,146 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// 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. - -/*! - * @file AckermannDrivePubSubTypes.h - * This header file contains the declaration of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - - -#ifndef _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVE_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVE_PUBSUBTYPES_H_ - -#include -#include - -#include "AckermannDrive.h" - - -#if !defined(GEN_API_VER) || (GEN_API_VER != 1) -#error \ - Generated AckermannDrive is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. -#endif // GEN_API_VER - -namespace ackermann_msgs -{ - namespace msg - { - - #ifndef SWIG - namespace detail { - - template - struct AckermannDrive_rob - { - friend constexpr typename Tag::type get( - Tag) - { - return M; - } - }; - - struct AckermannDrive_f - { - typedef float AckermannDrive::* type; - friend constexpr type get( - AckermannDrive_f); - }; - - template struct AckermannDrive_rob; - - template - inline size_t constexpr AckermannDrive_offset_of() { - return ((::size_t) &reinterpret_cast((((T*)0)->*get(Tag())))); - } - } - #endif - - /*! - * @brief This class represents the TopicDataType of the type AckermannDrive defined by the user in the IDL file. - * @ingroup AckermannDrive - */ - class AckermannDrivePubSubType : public eprosima::fastdds::dds::TopicDataType - { - public: - - typedef AckermannDrive type; - - eProsima_user_DllExport AckermannDrivePubSubType(); - - eProsima_user_DllExport virtual ~AckermannDrivePubSubType() override; - - eProsima_user_DllExport virtual bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; - - eProsima_user_DllExport virtual bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, - void* data) override; - - eProsima_user_DllExport virtual std::function getSerializedSizeProvider( - void* data) override; - - eProsima_user_DllExport virtual bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport virtual void* createData() override; - - eProsima_user_DllExport virtual void deleteData( - void* data) override; - - #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return true; - } - - #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - - #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return is_plain_impl(); - } - - #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - new (memory) AckermannDrive(); - return true; - } - - #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - - MD5 m_md5; - unsigned char* m_keyBuffer; - - private: - - static constexpr bool is_plain_impl() - { - return 20ULL == (detail::AckermannDrive_offset_of() + sizeof(float)); - - }}; - } -} - -#endif // _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVE_PUBSUBTYPES_H_ - diff --git a/LibCarla/source/carla/ros2/types/ActorDefinition.h b/LibCarla/source/carla/ros2/types/ActorDefinition.h new file mode 100644 index 00000000000..f2e1939d2bd --- /dev/null +++ b/LibCarla/source/carla/ros2/types/ActorDefinition.h @@ -0,0 +1,39 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/geom/BoundingBox.h" +#include "carla/ros2/types/ActorNameDefinition.h" +#include "carla/ros2/types/Polygon.h" +#include "carla/ros2/types/Transform.h" + +namespace carla { +namespace ros2 { +namespace types { + +using ActorSetTransformCallback = std::function; + +struct ActorDefinition : public ActorNameDefinition { + ActorDefinition(ActorNameDefinition const &actor_name_definition, carla::geom::BoundingBox bounding_box_, + carla::ros2::types::Polygon vertex_polygon_) + : ActorNameDefinition(actor_name_definition), bounding_box(bounding_box_), vertex_polygon(vertex_polygon_) {} + + carla::geom::BoundingBox bounding_box; + carla::ros2::types::Polygon vertex_polygon; +}; + + + +} // namespace types +} // namespace ros2 +} // namespace carla + +namespace std { + +inline std::string to_string(carla::ros2::types::ActorDefinition const &actor_definition) { + return "Actor(" + to_string(static_cast(actor_definition)) + ")"; +} + +} // namespace std \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/ActorNameDefinition.cpp b/LibCarla/source/carla/ros2/types/ActorNameDefinition.cpp new file mode 100644 index 00000000000..7930755d9c9 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/ActorNameDefinition.cpp @@ -0,0 +1,33 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/ros2/types/ActorNameDefinition.h" + +#include "carla/ros2/ROS2NameRegistry.h" + +namespace carla { +namespace ros2 { +namespace types { + +carla_msgs::msg::CarlaActorInfo ActorNameDefinition::carla_actor_info(std::shared_ptr name_registry) const { + carla_msgs::msg::CarlaActorInfo actor_info; + actor_info.id(id); + actor_info.parent_id(name_registry->ParentActorId(id)); + actor_info.type(type_id); + actor_info.rosname(ros_name); + actor_info.rolename(role_name); + actor_info.object_type(object_type); + actor_info.base_type(base_type); + auto topic_prefix = name_registry->TopicPrefix(id); + if ( topic_prefix.length() >= 3 ) + { + // remove "rt" prefix + actor_info.topic_prefix(topic_prefix.substr(3)); + } + return actor_info; +} + +} // namespace types +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/types/ActorNameDefinition.h b/LibCarla/source/carla/ros2/types/ActorNameDefinition.h new file mode 100644 index 00000000000..5cab6f4c308 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/ActorNameDefinition.h @@ -0,0 +1,62 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include + +#include "carla/streaming/detail/Types.h" +#include "carla_msgs/msg/CarlaActorInfo.h" + +namespace carla { +namespace ros2 { + +class ROS2NameRegistry; + +namespace types { + +struct ActorNameDefinition { + ActorNameDefinition(carla::streaming::detail::actor_id_type id_ = 0u, std::string type_id_ = "", std::string ros_name_ = "", + std::string role_name_ = "", std::string object_type_ = "", std::string base_type_ = "", bool enabled_for_ros_ = false) + : id(id_), + type_id(type_id_), + ros_name(ros_name_), + role_name(role_name_), + object_type(object_type_), + base_type(base_type_), + enabled_for_ros(enabled_for_ros_) {} + + static std::shared_ptr CreateFromRoleName(std::string const &role_name_, bool enabled_for_ros_ = false) { + auto actor_name_definition = std::make_shared(); + actor_name_definition->role_name = role_name_; + actor_name_definition->enabled_for_ros = enabled_for_ros_; + return actor_name_definition; + } + + carla_msgs::msg::CarlaActorInfo carla_actor_info(std::shared_ptr name_registry) const; + + virtual ~ActorNameDefinition() = default; + + carla::streaming::detail::actor_id_type id; + std::string type_id; + std::string ros_name; + std::string role_name; + std::string object_type; + std::string base_type; + bool enabled_for_ros; +}; +} // namespace types +} // namespace ros2 +} // namespace carla + +namespace std { + +inline std::string to_string(carla::ros2::types::ActorNameDefinition const &actor_definition) { + return "ActorName(actor_id=" + std::to_string(actor_definition.id) + " type_id=" + actor_definition.type_id + + " ros_name=" + actor_definition.ros_name + " role_name=" + actor_definition.role_name + + " object_type=" + actor_definition.object_type + " base_type=" + actor_definition.base_type + + " enabled_for_ros=" + std::to_string(actor_definition.enabled_for_ros) + ")"; +} + +} // namespace std \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/AngularVelocity.h b/LibCarla/source/carla/ros2/types/AngularVelocity.h new file mode 100644 index 00000000000..0480f85aa27 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/AngularVelocity.h @@ -0,0 +1,68 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/geom/AngularVelocity.h" +#include "carla/geom/Math.h" +#include "geometry_msgs/msg/Accel.h" + +namespace carla { +namespace ros2 { +namespace types { + +/** + Convert a carla AngularVelocity to a ROS accel + + Considers the conversion from left-handed system (unreal) to right-handed + system (ROS) + +*/ +class AngularVelocity { +public: + AngularVelocity() = default; + ~AngularVelocity() = default; + AngularVelocity(const AngularVelocity&) = default; + AngularVelocity& operator=(const AngularVelocity&) = default; + AngularVelocity(AngularVelocity&&) = default; + AngularVelocity& operator=(AngularVelocity&&) = default; + + /** + * carla_AngularVelocity: the carla linear AngularVelocity + */ + explicit AngularVelocity(const carla::geom::AngularVelocity& carla_angular_velocity) { + _angular_velocity_ros.x = -carla::geom::Math::ToRadians(carla_angular_velocity.x); // -(forward = forward) + _angular_velocity.x(_angular_velocity_ros.x); + _angular_velocity_ros.y = carla::geom::Math::ToRadians(carla_angular_velocity.y); // -( right = -left ) + _angular_velocity.y(_angular_velocity_ros.y); + _angular_velocity_ros.z = -carla::geom::Math::ToRadians(carla_angular_velocity.z); // -( up = up ) + _angular_velocity.z(_angular_velocity_ros.z); + } +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + AngularVelocity(const FVector& carla_angular_velocity) + : AngularVelocity( + carla::geom::Vector3D(carla_angular_velocity.X, carla_angular_velocity.Y, carla_angular_velocity.Z)) {} +#endif // LIBCARLA_INCLUDED_FROM_UE4 + + /** + * The resulting ROS geometry_msgs::msg::Vector3 + */ + geometry_msgs::msg::Vector3 angular_velocity() const { + return _angular_velocity; + } + + /** + * The angular velocity as carla::geom::Vector3D but in ROS coordinates + */ + carla::geom::AngularVelocity AngularVelocityROS() const { + return _angular_velocity_ros; + } + +private: + carla::geom::AngularVelocity _angular_velocity_ros; + geometry_msgs::msg::Vector3 _angular_velocity; +}; +} // namespace types +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/CameraInfo.h b/LibCarla/source/carla/ros2/types/CameraInfo.h deleted file mode 100644 index b4c4322e82f..00000000000 --- a/LibCarla/source/carla/ros2/types/CameraInfo.h +++ /dev/null @@ -1,451 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// 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. - -/*! - * @file CameraInfo.h - * This header file contains the declaration of the described types in the IDL file. - * - * This file was generated by the tool gen. - */ - -#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFO_H_ -#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFO_H_ - -#include "RegionOfInterest.h" -#include "Header.h" - -#include - -#include -#include -#include -#include -#include -#include - -#if defined(_WIN32) -#if defined(EPROSIMA_USER_DLL_EXPORT) -#define eProsima_user_DllExport __declspec( dllexport ) -#else -#define eProsima_user_DllExport -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define eProsima_user_DllExport -#endif // _WIN32 - -#if defined(_WIN32) -#if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(CAMERAINFO_SOURCE) -#define CAMERAINFO_DllAPI __declspec( dllexport ) -#else -#define CAMERAINFO_DllAPI __declspec( dllimport ) -#endif // CAMERAINFO_SOURCE -#else -#define CAMERAINFO_DllAPI -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define CAMERAINFO_DllAPI -#endif // _WIN32 - -namespace eprosima { -namespace fastcdr { -class Cdr; -} // namespace fastcdr -} // namespace eprosima - -namespace sensor_msgs { - namespace msg { - /*! - * @brief This class represents the structure CameraInfo defined by the user in the IDL file. - * @ingroup CameraInfo - */ - class CameraInfo - { - public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport CameraInfo(uint32_t height = 0, uint32_t width = 0, double fov = 0.0); - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~CameraInfo(); - - /*! - * @brief Copy constructor. - * @param x Reference to the object sensor_msgs::msg::CameraInfo that will be copied. - */ - eProsima_user_DllExport CameraInfo( - const CameraInfo& x); - - /*! - * @brief Move constructor. - * @param x Reference to the object sensor_msgs::msg::CameraInfo that will be copied. - */ - eProsima_user_DllExport CameraInfo( - CameraInfo&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object sensor_msgs::msg::CameraInfo that will be copied. - */ - eProsima_user_DllExport CameraInfo& operator =( - const CameraInfo& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object sensor_msgs::msg::CameraInfo that will be copied. - */ - eProsima_user_DllExport CameraInfo& operator =( - CameraInfo&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x sensor_msgs::msg::CameraInfo object to compare. - */ - eProsima_user_DllExport bool operator ==( - const CameraInfo& x) const; - - /*! - * @brief Comparison operator. - * @param x sensor_msgs::msg::CameraInfo object to compare. - */ - eProsima_user_DllExport bool operator !=( - const CameraInfo& x) const; - - /*! - * @brief This function copies the value in member header - * @param _header New value to be copied in member header - */ - eProsima_user_DllExport void header( - const std_msgs::msg::Header& _header); - - /*! - * @brief This function moves the value in member header - * @param _header New value to be moved in member header - */ - eProsima_user_DllExport void header( - std_msgs::msg::Header&& _header); - - /*! - * @brief This function returns a constant reference to member header - * @return Constant reference to member header - */ - eProsima_user_DllExport const std_msgs::msg::Header& header() const; - - /*! - * @brief This function returns a reference to member header - * @return Reference to member header - */ - eProsima_user_DllExport std_msgs::msg::Header& header(); - /*! - * @brief This function sets a value in member height - * @param _height New value for member height - */ - eProsima_user_DllExport void height( - uint32_t _height); - - /*! - * @brief This function returns the value of member height - * @return Value of member height - */ - eProsima_user_DllExport uint32_t height() const; - - /*! - * @brief This function returns a reference to member height - * @return Reference to member height - */ - eProsima_user_DllExport uint32_t& height(); - - /*! - * @brief This function sets a value in member width - * @param _width New value for member width - */ - eProsima_user_DllExport void width( - uint32_t _width); - - /*! - * @brief This function returns the value of member width - * @return Value of member width - */ - eProsima_user_DllExport uint32_t width() const; - - /*! - * @brief This function returns a reference to member width - * @return Reference to member width - */ - eProsima_user_DllExport uint32_t& width(); - - /*! - * @brief This function copies the value in member distortion_model - * @param _distortion_model New value to be copied in member distortion_model - */ - eProsima_user_DllExport void distortion_model( - const std::string& _distortion_model); - - /*! - * @brief This function moves the value in member distortion_model - * @param _distortion_model New value to be moved in member distortion_model - */ - eProsima_user_DllExport void distortion_model( - std::string&& _distortion_model); - - /*! - * @brief This function returns a constant reference to member distortion_model - * @return Constant reference to member distortion_model - */ - eProsima_user_DllExport const std::string& distortion_model() const; - - /*! - * @brief This function returns a reference to member distortion_model - * @return Reference to member distortion_model - */ - eProsima_user_DllExport std::string& distortion_model(); - /*! - * @brief This function copies the value in member D - * @param _D New value to be copied in member D - */ - eProsima_user_DllExport void D( - const std::vector& _D); - - /*! - * @brief This function moves the value in member D - * @param _D New value to be moved in member D - */ - eProsima_user_DllExport void D( - std::vector&& _D); - - /*! - * @brief This function returns a constant reference to member D - * @return Constant reference to member D - */ - eProsima_user_DllExport const std::vector& D() const; - - /*! - * @brief This function returns a reference to member D - * @return Reference to member D - */ - eProsima_user_DllExport std::vector& D(); - /*! - * @brief This function copies the value in member K - * @param _K New value to be copied in member K - */ - eProsima_user_DllExport void k( - const std::array& _k); - - /*! - * @brief This function moves the value in member k - * @param _k New value to be moved in member k - */ - eProsima_user_DllExport void k( - std::array&& _k); - - /*! - * @brief This function returns a constant reference to member k - * @return Constant reference to member k - */ - eProsima_user_DllExport const std::array& k() const; - - /*! - * @brief This function returns a reference to member k - * @return Reference to member k - */ - eProsima_user_DllExport std::array& k(); - /*! - * @brief This function copies the value in member r - * @param _r New value to be copied in member r - */ - eProsima_user_DllExport void r( - const std::array& _r); - - /*! - * @brief This function moves the value in member r - * @param _r New value to be moved in member r - */ - eProsima_user_DllExport void r( - std::array&& _r); - - /*! - * @brief This function returns a constant reference to member r - * @return Constant reference to member r - */ - eProsima_user_DllExport const std::array& r() const; - - /*! - * @brief This function returns a reference to member r - * @return Reference to member r - */ - eProsima_user_DllExport std::array& r(); - /*! - * @brief This function copies the value in member p - * @param _p New value to be copied in member p - */ - eProsima_user_DllExport void p( - const std::array& _p); - - /*! - * @brief This function moves the value in member p - * @param _p New value to be moved in member p - */ - eProsima_user_DllExport void p( - std::array&& _p); - - /*! - * @brief This function returns a constant reference to member p - * @return Constant reference to member p - */ - eProsima_user_DllExport const std::array& p() const; - - /*! - * @brief This function returns a reference to member p - * @return Reference to member p - */ - eProsima_user_DllExport std::array& p(); - /*! - * @brief This function sets a value in member binning_x - * @param _binning_x New value for member binning_x - */ - eProsima_user_DllExport void binning_x( - uint32_t _binning_x); - - /*! - * @brief This function returns the value of member binning_x - * @return Value of member binning_x - */ - eProsima_user_DllExport uint32_t binning_x() const; - - /*! - * @brief This function returns a reference to member binning_x - * @return Reference to member binning_x - */ - eProsima_user_DllExport uint32_t& binning_x(); - - /*! - * @brief This function sets a value in member binning_y - * @param _binning_y New value for member binning_y - */ - eProsima_user_DllExport void binning_y( - uint32_t _binning_y); - - /*! - * @brief This function returns the value of member binning_y - * @return Value of member binning_y - */ - eProsima_user_DllExport uint32_t binning_y() const; - - /*! - * @brief This function returns a reference to member binning_y - * @return Reference to member binning_y - */ - eProsima_user_DllExport uint32_t& binning_y(); - - /*! - * @brief This function copies the value in member roi - * @param _roi New value to be copied in member roi - */ - eProsima_user_DllExport void roi( - const sensor_msgs::msg::RegionOfInterest& _roi); - - /*! - * @brief This function moves the value in member roi - * @param _roi New value to be moved in member roi - */ - eProsima_user_DllExport void roi( - sensor_msgs::msg::RegionOfInterest&& _roi); - - /*! - * @brief This function returns a constant reference to member roi - * @return Constant reference to member roi - */ - eProsima_user_DllExport const sensor_msgs::msg::RegionOfInterest& roi() const; - - /*! - * @brief This function returns a reference to member roi - * @return Reference to member roi - */ - eProsima_user_DllExport sensor_msgs::msg::RegionOfInterest& roi(); - - /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ - eProsima_user_DllExport static size_t getMaxCdrSerializedSize( - size_t current_alignment = 0); - - /*! - * @brief This function returns the serialized size of a data depending on the buffer alignment. - * @param data Data which is calculated its serialized size. - * @param current_alignment Buffer alignment. - * @return Serialized size. - */ - eProsima_user_DllExport static size_t getCdrSerializedSize( - const sensor_msgs::msg::CameraInfo& data, - size_t current_alignment = 0); - - /*! - * @brief This function serializes an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& cdr) const; - - /*! - * @brief This function deserializes an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr); - - /*! - * @brief This function returns the maximum serialized size of the Key of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ - eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( - size_t current_alignment = 0); - - /*! - * @brief This function tells you if the Key has been defined for this type - */ - eProsima_user_DllExport static bool isKeyDefined(); - - /*! - * @brief This function serializes the key members of an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void serializeKey( - eprosima::fastcdr::Cdr& cdr) const; - - private: - std_msgs::msg::Header m_header; - uint32_t m_height; - uint32_t m_width; - std::string m_distortion_model; - std::vector m_d; - std::array m_k; - std::array m_r; - std::array m_p; - uint32_t m_binning_x; - uint32_t m_binning_y; - sensor_msgs::msg::RegionOfInterest m_roi; - }; - } // namespace msg -} // namespace sensor_msgs - -#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFO_H_ diff --git a/LibCarla/source/carla/ros2/types/CoordinateSystemTransform.h b/LibCarla/source/carla/ros2/types/CoordinateSystemTransform.h new file mode 100644 index 00000000000..db65e49a0b4 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/CoordinateSystemTransform.h @@ -0,0 +1,59 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/geom/Vector3D.h" +#include "geometry_msgs/msg/Point32.h" +#include "geometry_msgs/msg/Vector3.h" + +namespace carla { +namespace ros2 { +namespace types { + +/** + Convert a carla (linear) CoordinateSystemTransform to a ROS accel (linear part) + + Considers the conversion from left-handed system (unreal) to right-handed + system (ROS) +*/ +class CoordinateSystemTransform { +public: + /** + * @param \in carla_linear_values: the carla linear values provided provided by UE4 coordinate system + * @returns values in ROS coordinate system (x:forward = forward, y: right = -left, z; up = up) + */ + static geometry_msgs::msg::Vector3 TransformLinearAxisMsg(carla::geom::Location const &carla_linear_values) { + geometry_msgs::msg::Vector3 result; + result.x(carla_linear_values.x); + result.y(-carla_linear_values.y); + result.z(carla_linear_values.z); + return result; + } + + static geometry_msgs::msg::Point32 TransformLocationToPoint32Msg(carla::geom::Location const &carla_location) { + geometry_msgs::msg::Point32 result; + result.x(carla_location.x); + result.y(-carla_location.y); + result.z(carla_location.z); + return result; + } + + static geometry_msgs::msg::Vector3 TransformLocationToVector3Msg(carla::geom::Location const &carla_location) { + geometry_msgs::msg::Vector3 result; + result.x(carla_location.x); + result.y(-carla_location.y); + result.z(carla_location.z); + return result; + } + + static carla::geom::Location TransformLinearAxixVector3D(carla::geom::Location const &carla_linear_values) { + carla::geom::Location result(carla_linear_values); + result.y = -result.y; + return result; + } +}; +} // namespace types +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/EpisodeSettings.h b/LibCarla/source/carla/ros2/types/EpisodeSettings.h new file mode 100644 index 00000000000..c557f0bdee8 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/EpisodeSettings.h @@ -0,0 +1,72 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/rpc/EpisodeSettings.h" +#include "carla_msgs/msg/CarlaEpisodeSettings.h" + +namespace carla { +namespace ros2 { +namespace types { + +/** + Convert a carla EpisodeSettings to a ROS CarlaEpisodeSettings and vice-vera +*/ +class EpisodeSettings { +public: + explicit EpisodeSettings(carla::rpc::EpisodeSettings const& rpc_episode_settings = carla::rpc::EpisodeSettings()) { + _ros_episode_settings.synchronous_mode(rpc_episode_settings.synchronous_mode); + _ros_episode_settings.no_rendering_mode(rpc_episode_settings.no_rendering_mode); + if ( rpc_episode_settings.fixed_delta_seconds.has_value() ) { + _ros_episode_settings.fixed_delta_seconds(rpc_episode_settings.fixed_delta_seconds.value()); + } + _ros_episode_settings.substepping(rpc_episode_settings.substepping); + _ros_episode_settings.max_substep_delta_time(rpc_episode_settings.max_substep_delta_time); + _ros_episode_settings.max_substeps(rpc_episode_settings.max_substeps); + _ros_episode_settings.max_culling_distance(rpc_episode_settings.max_culling_distance); + _ros_episode_settings.deterministic_ragdolls(rpc_episode_settings.deterministic_ragdolls); + _ros_episode_settings.tile_stream_distance(rpc_episode_settings.tile_stream_distance); + _ros_episode_settings.actor_active_distance(rpc_episode_settings.actor_active_distance); + _ros_episode_settings.spectator_as_ego(rpc_episode_settings.spectator_as_ego); + } + + explicit EpisodeSettings(carla_msgs::msg::CarlaEpisodeSettings const& carla_episode_settings) { + _ros_episode_settings = carla_episode_settings; + } + ~EpisodeSettings() = default; + EpisodeSettings(const EpisodeSettings&) = default; + EpisodeSettings& operator=(const EpisodeSettings&) = default; + EpisodeSettings(EpisodeSettings&&) = default; + EpisodeSettings& operator=(EpisodeSettings&&) = default; + + /** + * The resulting ROS carla_msgs::msg::CarlaEpisodeSettings + */ + carla_msgs::msg::CarlaEpisodeSettings episode_settings() const { + return _ros_episode_settings; + } + + carla::rpc::EpisodeSettings GetEpisodeSettings() const { + carla::rpc::EpisodeSettings episode_settings; + episode_settings.synchronous_mode = _ros_episode_settings.synchronous_mode(); + episode_settings.no_rendering_mode = _ros_episode_settings.no_rendering_mode(); + episode_settings.fixed_delta_seconds = _ros_episode_settings.fixed_delta_seconds(); + episode_settings.substepping = _ros_episode_settings.substepping(); + episode_settings.max_substep_delta_time = _ros_episode_settings.max_substep_delta_time(); + episode_settings.max_substeps = _ros_episode_settings.max_substeps(); + episode_settings.max_culling_distance = _ros_episode_settings.max_culling_distance(); + episode_settings.deterministic_ragdolls = _ros_episode_settings.deterministic_ragdolls(); + episode_settings.tile_stream_distance = _ros_episode_settings.tile_stream_distance(); + episode_settings.actor_active_distance = _ros_episode_settings.actor_active_distance(); + episode_settings.spectator_as_ego = _ros_episode_settings.spectator_as_ego(); + return episode_settings; + } + +private: + carla_msgs::msg::CarlaEpisodeSettings _ros_episode_settings; +}; +} // namespace types +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/Float32PubSubTypes.h b/LibCarla/source/carla/ros2/types/Float32PubSubTypes.h deleted file mode 100644 index 4915efbbd45..00000000000 --- a/LibCarla/source/carla/ros2/types/Float32PubSubTypes.h +++ /dev/null @@ -1,139 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// 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. - -/*! - * @file Float32PubSubTypes.h - * This header file contains the declaration of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#ifndef _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32_PUBSUBTYPES_H_ - -#include -#include - -#include "Float32.h" - -#if !defined(GEN_API_VER) || (GEN_API_VER != 1) -#error \ - Generated Float32 is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. -#endif // GEN_API_VER - -namespace std_msgs -{ - namespace msg - { - #ifndef SWIG - namespace detail { - template - struct Float32_rob - { - friend constexpr typename Tag::type get( - Tag) - { - return M; - } - }; - - struct Float32_f - { - typedef float Float32::* type; - friend constexpr type get( - Float32_f); - }; - - template struct Float32_rob; - - template - inline size_t constexpr Float32_offset_of() { - return ((::size_t) &reinterpret_cast((((T*)0)->*get(Tag())))); - } - } - #endif - - /*! - * @brief This class represents the TopicDataType of the type Float32 defined by the user in the IDL file. - * @ingroup FLOAT32 - */ - class Float32PubSubType : public eprosima::fastdds::dds::TopicDataType - { - public: - - typedef Float32 type; - - eProsima_user_DllExport Float32PubSubType(); - - eProsima_user_DllExport virtual ~Float32PubSubType() override; - - eProsima_user_DllExport virtual bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; - - eProsima_user_DllExport virtual bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, - void* data) override; - - eProsima_user_DllExport virtual std::function getSerializedSizeProvider( - void* data) override; - - eProsima_user_DllExport virtual bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport virtual void* createData() override; - - eProsima_user_DllExport virtual void deleteData( - void* data) override; - - #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return true; - } - - #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - - #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return is_plain_impl(); - } - - #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - new (memory) Float32(); - return true; - } - - #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; - unsigned char* m_keyBuffer; - - private: - static constexpr bool is_plain_impl() - { - return 4ULL == (detail::Float32_offset_of() + sizeof(float)); - - }}; - } -} - -#endif // _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/Image.cpp b/LibCarla/source/carla/ros2/types/Image.cpp deleted file mode 100644 index 1946f876695..00000000000 --- a/LibCarla/source/carla/ros2/types/Image.cpp +++ /dev/null @@ -1,423 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// 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. - -/*! - * @file Image.cpp - * This source file contains the definition of the described types in the IDL file. - * - * This file was generated by the tool gen. - */ - -#ifdef _WIN32 -// Remove linker warning LNK4221 on Visual Studio -namespace { -char dummy; -} // namespace -#endif // _WIN32 - -#include "Image.h" -#include - -#include -using namespace eprosima::fastcdr::exception; - -#include - -#define builtin_interfaces_msg_Time_max_cdr_typesize 8ULL; -#define sensor_msgs_msg_Image_max_cdr_typesize 648ULL; -#define std_msgs_msg_Header_max_cdr_typesize 268ULL; -#define builtin_interfaces_msg_Time_max_key_cdr_typesize 0ULL; -#define sensor_msgs_msg_Image_max_key_cdr_typesize 0ULL; -#define std_msgs_msg_Header_max_key_cdr_typesize 0ULL; - -sensor_msgs::msg::Image::Image() -{ - // std_msgs::msg::Header m_header - - // unsigned long m_height - m_height = 0; - // unsigned long m_width - m_width = 0; - // string m_encoding - m_encoding =""; - // uint8 m_is_bigendian - m_is_bigendian = 0; - // unsigned long m_step - m_step = 0; - // sequence m_data -} - -sensor_msgs::msg::Image::~Image() -{ -} - -sensor_msgs::msg::Image::Image( - const Image& x) -{ - m_header = x.m_header; - m_height = x.m_height; - m_width = x.m_width; - m_encoding = x.m_encoding; - m_is_bigendian = x.m_is_bigendian; - m_step = x.m_step; - m_data = x.m_data; -} - -sensor_msgs::msg::Image::Image( - Image&& x) noexcept -{ - m_header = std::move(x.m_header); - m_height = x.m_height; - m_width = x.m_width; - m_encoding = std::move(x.m_encoding); - m_is_bigendian = x.m_is_bigendian; - m_step = x.m_step; - m_data = std::move(x.m_data); -} - -sensor_msgs::msg::Image& sensor_msgs::msg::Image::operator =( - const Image& x) -{ - m_header = x.m_header; - m_height = x.m_height; - m_width = x.m_width; - m_encoding = x.m_encoding; - m_is_bigendian = x.m_is_bigendian; - m_step = x.m_step; - m_data = x.m_data; - - return *this; -} - -sensor_msgs::msg::Image& sensor_msgs::msg::Image::operator =( - Image&& x) noexcept -{ - m_header = std::move(x.m_header); - m_height = x.m_height; - m_width = x.m_width; - m_encoding = std::move(x.m_encoding); - m_is_bigendian = x.m_is_bigendian; - m_step = x.m_step; - m_data = std::move(x.m_data); - - return *this; -} - -bool sensor_msgs::msg::Image::operator ==( - const Image& x) const -{ - return (m_header == x.m_header && m_height == x.m_height && m_width == x.m_width && m_encoding == x.m_encoding && m_is_bigendian == x.m_is_bigendian && m_step == x.m_step && m_data == x.m_data); -} - -bool sensor_msgs::msg::Image::operator !=( - const Image& x) const -{ - return !(*this == x); -} - -size_t sensor_msgs::msg::Image::getMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return sensor_msgs_msg_Image_max_cdr_typesize; -} - -size_t sensor_msgs::msg::Image::getCdrSerializedSize( - const sensor_msgs::msg::Image& data, - size_t current_alignment) -{ - size_t initial_alignment = current_alignment; - current_alignment += std_msgs::msg::Header::getCdrSerializedSize(data.header(), current_alignment); - current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); - current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); - current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.encoding().size() + 1; - current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); - current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); - current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); - - if (data.data().size() > 0) - { - current_alignment += (data.data().size() * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); - } - - return current_alignment - initial_alignment; -} - -void sensor_msgs::msg::Image::serialize( - eprosima::fastcdr::Cdr& scdr) const -{ - scdr << m_header; - scdr << m_height; - scdr << m_width; - scdr << m_encoding.c_str(); - scdr << m_is_bigendian; - scdr << m_step; - scdr << m_data; -} - -void sensor_msgs::msg::Image::deserialize( - eprosima::fastcdr::Cdr& dcdr) -{ - dcdr >> m_header; - dcdr >> m_height; - dcdr >> m_width; - dcdr >> m_encoding; - dcdr >> m_is_bigendian; - dcdr >> m_step; - dcdr >> m_data; -} - -/*! - * @brief This function copies the value in member header - * @param _header New value to be copied in member header - */ -void sensor_msgs::msg::Image::header( - const std_msgs::msg::Header& _header) -{ - m_header = _header; -} - -/*! - * @brief This function moves the value in member header - * @param _header New value to be moved in member header - */ -void sensor_msgs::msg::Image::header( - std_msgs::msg::Header&& _header) -{ - m_header = std::move(_header); -} - -/*! - * @brief This function returns a constant reference to member header - * @return Constant reference to member header - */ -const std_msgs::msg::Header& sensor_msgs::msg::Image::header() const -{ - return m_header; -} - -/*! - * @brief This function returns a reference to member header - * @return Reference to member header - */ -std_msgs::msg::Header& sensor_msgs::msg::Image::header() -{ - return m_header; -} - -/*! - * @brief This function sets a value in member height - * @param _height New value for member height - */ -void sensor_msgs::msg::Image::height( - uint32_t _height) -{ - m_height = _height; -} - -/*! - * @brief This function returns the value of member height - * @return Value of member height - */ -uint32_t sensor_msgs::msg::Image::height() const -{ - return m_height; -} - -/*! - * @brief This function returns a reference to member height - * @return Reference to member height - */ -uint32_t& sensor_msgs::msg::Image::height() -{ - return m_height; -} - -/*! - * @brief This function sets a value in member width - * @param _width New value for member width - */ -void sensor_msgs::msg::Image::width( - uint32_t _width) -{ - m_width = _width; -} - -/*! - * @brief This function returns the value of member width - * @return Value of member width - */ -uint32_t sensor_msgs::msg::Image::width() const -{ - return m_width; -} - -/*! - * @brief This function returns a reference to member width - * @return Reference to member width - */ -uint32_t& sensor_msgs::msg::Image::width() -{ - return m_width; -} - -/*! - * @brief This function copies the value in member encoding - * @param _encoding New value to be copied in member encoding - */ -void sensor_msgs::msg::Image::encoding( - const std::string& _encoding) -{ - m_encoding = _encoding; -} - -/*! - * @brief This function moves the value in member encoding - * @param _encoding New value to be moved in member encoding - */ -void sensor_msgs::msg::Image::encoding( - std::string&& _encoding) -{ - m_encoding = std::move(_encoding); -} - -/*! - * @brief This function returns a constant reference to member encoding - * @return Constant reference to member encoding - */ -const std::string& sensor_msgs::msg::Image::encoding() const -{ - return m_encoding; -} - -/*! - * @brief This function returns a reference to member encoding - * @return Reference to member encoding - */ -std::string& sensor_msgs::msg::Image::encoding() -{ - return m_encoding; -} - -/*! - * @brief This function sets a value in member is_bigendian - * @param _is_bigendian New value for member is_bigendian - */ -void sensor_msgs::msg::Image::is_bigendian( - uint8_t _is_bigendian) -{ - m_is_bigendian = _is_bigendian; -} - -/*! - * @brief This function returns the value of member is_bigendian - * @return Value of member is_bigendian - */ -uint8_t sensor_msgs::msg::Image::is_bigendian() const -{ - return m_is_bigendian; -} - -/*! - * @brief This function returns a reference to member is_bigendian - * @return Reference to member is_bigendian - */ -uint8_t& sensor_msgs::msg::Image::is_bigendian() -{ - return m_is_bigendian; -} - -/*! - * @brief This function sets a value in member step - * @param _step New value for member step - */ -void sensor_msgs::msg::Image::step( - uint32_t _step) -{ - m_step = _step; -} - -/*! - * @brief This function returns the value of member step - * @return Value of member step - */ -uint32_t sensor_msgs::msg::Image::step() const -{ - return m_step; -} - -/*! - * @brief This function returns a reference to member step - * @return Reference to member step - */ -uint32_t& sensor_msgs::msg::Image::step() -{ - return m_step; -} - -/*! - * @brief This function copies the value in member data - * @param _data New value to be copied in member data - */ -void sensor_msgs::msg::Image::data( - const std::vector& _data) -{ - m_data = _data; -} - -/*! - * @brief This function moves the value in member data - * @param _data New value to be moved in member data - */ -void sensor_msgs::msg::Image::data( - std::vector&& _data) -{ - m_data = std::move(_data); -} - -/*! - * @brief This function returns a constant reference to member data - * @return Constant reference to member data - */ -const std::vector& sensor_msgs::msg::Image::data() const -{ - return m_data; -} - -/*! - * @brief This function returns a reference to member data - * @return Reference to member data - */ -std::vector& sensor_msgs::msg::Image::data() -{ - return m_data; -} - -size_t sensor_msgs::msg::Image::getKeyMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return sensor_msgs_msg_Image_max_key_cdr_typesize; -} - -bool sensor_msgs::msg::Image::isKeyDefined() -{ - return false; -} - -void sensor_msgs::msg::Image::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} diff --git a/LibCarla/source/carla/ros2/types/Imu.h b/LibCarla/source/carla/ros2/types/Imu.h deleted file mode 100644 index 4d8f45b02ed..00000000000 --- a/LibCarla/source/carla/ros2/types/Imu.h +++ /dev/null @@ -1,373 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// 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. - -/*! - * @file Imu.h - * This header file contains the declaration of the described types in the IDL file. - * - * This file was generated by the tool gen. - */ - -#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMU_H_ -#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMU_H_ - -#include "Vector3.h" -#include "Quaternion.h" -#include "Header.h" - -#include - -#include -#include -#include -#include -#include -#include - -#if defined(_WIN32) -#if defined(EPROSIMA_USER_DLL_EXPORT) -#define eProsima_user_DllExport __declspec( dllexport ) -#else -#define eProsima_user_DllExport -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define eProsima_user_DllExport -#endif // _WIN32 - -#if defined(_WIN32) -#if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(Imu_SOURCE) -#define Imu_DllAPI __declspec( dllexport ) -#else -#define Imu_DllAPI __declspec( dllimport ) -#endif // Imu_SOURCE -#else -#define Imu_DllAPI -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define Imu_DllAPI -#endif // _WIN32 - -namespace eprosima { -namespace fastcdr { -class Cdr; -} // namespace fastcdr -} // namespace eprosima - -namespace sensor_msgs { - namespace msg { - typedef std::array sensor_msgs__Imu__double_array_9; - /*! - * @brief This class represents the structure Imu defined by the user in the IDL file. - * @ingroup IMU - */ - class Imu - { - public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport Imu(); - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~Imu(); - - /*! - * @brief Copy constructor. - * @param x Reference to the object sensor_msgs::msg::Imu that will be copied. - */ - eProsima_user_DllExport Imu( - const Imu& x); - - /*! - * @brief Move constructor. - * @param x Reference to the object sensor_msgs::msg::Imu that will be copied. - */ - eProsima_user_DllExport Imu( - Imu&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object sensor_msgs::msg::Imu that will be copied. - */ - eProsima_user_DllExport Imu& operator =( - const Imu& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object sensor_msgs::msg::Imu that will be copied. - */ - eProsima_user_DllExport Imu& operator =( - Imu&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x sensor_msgs::msg::Imu object to compare. - */ - eProsima_user_DllExport bool operator ==( - const Imu& x) const; - - /*! - * @brief Comparison operator. - * @param x sensor_msgs::msg::Imu object to compare. - */ - eProsima_user_DllExport bool operator !=( - const Imu& x) const; - - /*! - * @brief This function copies the value in member header - * @param _header New value to be copied in member header - */ - eProsima_user_DllExport void header( - const std_msgs::msg::Header& _header); - - /*! - * @brief This function moves the value in member header - * @param _header New value to be moved in member header - */ - eProsima_user_DllExport void header( - std_msgs::msg::Header&& _header); - - /*! - * @brief This function returns a constant reference to member header - * @return Constant reference to member header - */ - eProsima_user_DllExport const std_msgs::msg::Header& header() const; - - /*! - * @brief This function returns a reference to member header - * @return Reference to member header - */ - eProsima_user_DllExport std_msgs::msg::Header& header(); - /*! - * @brief This function copies the value in member orientation - * @param _orientation New value to be copied in member orientation - */ - eProsima_user_DllExport void orientation( - const geometry_msgs::msg::Quaternion& _orientation); - - /*! - * @brief This function moves the value in member orientation - * @param _orientation New value to be moved in member orientation - */ - eProsima_user_DllExport void orientation( - geometry_msgs::msg::Quaternion&& _orientation); - - /*! - * @brief This function returns a constant reference to member orientation - * @return Constant reference to member orientation - */ - eProsima_user_DllExport const geometry_msgs::msg::Quaternion& orientation() const; - - /*! - * @brief This function returns a reference to member orientation - * @return Reference to member orientation - */ - eProsima_user_DllExport geometry_msgs::msg::Quaternion& orientation(); - /*! - * @brief This function copies the value in member orientation_covariance - * @param _orientation_covariance New value to be copied in member orientation_covariance - */ - eProsima_user_DllExport void orientation_covariance( - const sensor_msgs::msg::sensor_msgs__Imu__double_array_9& _orientation_covariance); - - /*! - * @brief This function moves the value in member orientation_covariance - * @param _orientation_covariance New value to be moved in member orientation_covariance - */ - eProsima_user_DllExport void orientation_covariance( - sensor_msgs::msg::sensor_msgs__Imu__double_array_9&& _orientation_covariance); - - /*! - * @brief This function returns a constant reference to member orientation_covariance - * @return Constant reference to member orientation_covariance - */ - eProsima_user_DllExport const sensor_msgs::msg::sensor_msgs__Imu__double_array_9& orientation_covariance() const; - - /*! - * @brief This function returns a reference to member orientation_covariance - * @return Reference to member orientation_covariance - */ - eProsima_user_DllExport sensor_msgs::msg::sensor_msgs__Imu__double_array_9& orientation_covariance(); - /*! - * @brief This function copies the value in member angular_velocity - * @param _angular_velocity New value to be copied in member angular_velocity - */ - eProsima_user_DllExport void angular_velocity( - const geometry_msgs::msg::Vector3& _angular_velocity); - - /*! - * @brief This function moves the value in member angular_velocity - * @param _angular_velocity New value to be moved in member angular_velocity - */ - eProsima_user_DllExport void angular_velocity( - geometry_msgs::msg::Vector3&& _angular_velocity); - - /*! - * @brief This function returns a constant reference to member angular_velocity - * @return Constant reference to member angular_velocity - */ - eProsima_user_DllExport const geometry_msgs::msg::Vector3& angular_velocity() const; - - /*! - * @brief This function returns a reference to member angular_velocity - * @return Reference to member angular_velocity - */ - eProsima_user_DllExport geometry_msgs::msg::Vector3& angular_velocity(); - /*! - * @brief This function copies the value in member angular_velocity_covariance - * @param _angular_velocity_covariance New value to be copied in member angular_velocity_covariance - */ - eProsima_user_DllExport void angular_velocity_covariance( - const sensor_msgs::msg::sensor_msgs__Imu__double_array_9& _angular_velocity_covariance); - - /*! - * @brief This function moves the value in member angular_velocity_covariance - * @param _angular_velocity_covariance New value to be moved in member angular_velocity_covariance - */ - eProsima_user_DllExport void angular_velocity_covariance( - sensor_msgs::msg::sensor_msgs__Imu__double_array_9&& _angular_velocity_covariance); - - /*! - * @brief This function returns a constant reference to member angular_velocity_covariance - * @return Constant reference to member angular_velocity_covariance - */ - eProsima_user_DllExport const sensor_msgs::msg::sensor_msgs__Imu__double_array_9& angular_velocity_covariance() const; - - /*! - * @brief This function returns a reference to member angular_velocity_covariance - * @return Reference to member angular_velocity_covariance - */ - eProsima_user_DllExport sensor_msgs::msg::sensor_msgs__Imu__double_array_9& angular_velocity_covariance(); - /*! - * @brief This function copies the value in member linear_acceleration - * @param _linear_acceleration New value to be copied in member linear_acceleration - */ - eProsima_user_DllExport void linear_acceleration( - const geometry_msgs::msg::Vector3& _linear_acceleration); - - /*! - * @brief This function moves the value in member linear_acceleration - * @param _linear_acceleration New value to be moved in member linear_acceleration - */ - eProsima_user_DllExport void linear_acceleration( - geometry_msgs::msg::Vector3&& _linear_acceleration); - - /*! - * @brief This function returns a constant reference to member linear_acceleration - * @return Constant reference to member linear_acceleration - */ - eProsima_user_DllExport const geometry_msgs::msg::Vector3& linear_acceleration() const; - - /*! - * @brief This function returns a reference to member linear_acceleration - * @return Reference to member linear_acceleration - */ - eProsima_user_DllExport geometry_msgs::msg::Vector3& linear_acceleration(); - /*! - * @brief This function copies the value in member linear_acceleration_covariance - * @param _linear_acceleration_covariance New value to be copied in member linear_acceleration_covariance - */ - eProsima_user_DllExport void linear_acceleration_covariance( - const sensor_msgs::msg::sensor_msgs__Imu__double_array_9& _linear_acceleration_covariance); - - /*! - * @brief This function moves the value in member linear_acceleration_covariance - * @param _linear_acceleration_covariance New value to be moved in member linear_acceleration_covariance - */ - eProsima_user_DllExport void linear_acceleration_covariance( - sensor_msgs::msg::sensor_msgs__Imu__double_array_9&& _linear_acceleration_covariance); - - /*! - * @brief This function returns a constant reference to member linear_acceleration_covariance - * @return Constant reference to member linear_acceleration_covariance - */ - eProsima_user_DllExport const sensor_msgs::msg::sensor_msgs__Imu__double_array_9& linear_acceleration_covariance() const; - - /*! - * @brief This function returns a reference to member linear_acceleration_covariance - * @return Reference to member linear_acceleration_covariance - */ - eProsima_user_DllExport sensor_msgs::msg::sensor_msgs__Imu__double_array_9& linear_acceleration_covariance(); - - /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ - eProsima_user_DllExport static size_t getMaxCdrSerializedSize( - size_t current_alignment = 0); - - /*! - * @brief This function returns the serialized size of a data depending on the buffer alignment. - * @param data Data which is calculated its serialized size. - * @param current_alignment Buffer alignment. - * @return Serialized size. - */ - eProsima_user_DllExport static size_t getCdrSerializedSize( - const sensor_msgs::msg::Imu& data, - size_t current_alignment = 0); - - /*! - * @brief This function serializes an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& cdr) const; - - /*! - * @brief This function deserializes an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr); - - /*! - * @brief This function returns the maximum serialized size of the Key of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ - eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( - size_t current_alignment = 0); - - /*! - * @brief This function tells you if the Key has been defined for this type - */ - eProsima_user_DllExport static bool isKeyDefined(); - - /*! - * @brief This function serializes the key members of an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void serializeKey( - eprosima::fastcdr::Cdr& cdr) const; - - private: - std_msgs::msg::Header m_header; - geometry_msgs::msg::Quaternion m_orientation; - sensor_msgs::msg::sensor_msgs__Imu__double_array_9 m_orientation_covariance; - geometry_msgs::msg::Vector3 m_angular_velocity; - sensor_msgs::msg::sensor_msgs__Imu__double_array_9 m_angular_velocity_covariance; - geometry_msgs::msg::Vector3 m_linear_acceleration; - sensor_msgs::msg::sensor_msgs__Imu__double_array_9 m_linear_acceleration_covariance; - }; - } // namespace msg -} // namespace sensor_msgs - -#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMU_H_ diff --git a/LibCarla/source/carla/ros2/types/NavSatFix.h b/LibCarla/source/carla/ros2/types/NavSatFix.h deleted file mode 100644 index 3615c99bb5e..00000000000 --- a/LibCarla/source/carla/ros2/types/NavSatFix.h +++ /dev/null @@ -1,351 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// 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. - -/*! - * @file NavSatFix.h - * This header file contains the declaration of the described types in the IDL file. - * - * This file was generated by the tool gen. - */ - -#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIX_H_ -#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIX_H_ - -#include "Header.h" -#include "NavSatStatus.h" - -#include - -#include -#include -#include -#include -#include -#include - -#if defined(_WIN32) -#if defined(EPROSIMA_USER_DLL_EXPORT) -#define eProsima_user_DllExport __declspec( dllexport ) -#else -#define eProsima_user_DllExport -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define eProsima_user_DllExport -#endif // _WIN32 - -#if defined(_WIN32) -#if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(NavSatFix_SOURCE) -#define NavSatFix_DllAPI __declspec( dllexport ) -#else -#define NavSatFix_DllAPI __declspec( dllimport ) -#endif // NavSatFix_SOURCE -#else -#define NavSatFix_DllAPI -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define NavSatFix_DllAPI -#endif // _WIN32 - -namespace eprosima { -namespace fastcdr { -class Cdr; -} // namespace fastcdr -} // namespace eprosima - -namespace sensor_msgs { - namespace msg { - const uint8_t NavSatFix__COVARIANCE_TYPE_UNKNOWN = 0; - const uint8_t NavSatFix__COVARIANCE_TYPE_APPROXIMATED = 1; - const uint8_t NavSatFix__COVARIANCE_TYPE_DIAGONAL_KNOWN = 2; - const uint8_t NavSatFix__COVARIANCE_TYPE_KNOWN = 3; - typedef std::array sensor_msgs__NavSatFix__double_array_9; - /*! - * @brief This class represents the structure NavSatFix defined by the user in the IDL file. - * @ingroup NAVSATFIX - */ - class NavSatFix - { - public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport NavSatFix(); - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~NavSatFix(); - - /*! - * @brief Copy constructor. - * @param x Reference to the object sensor_msgs::msg::NavSatFix that will be copied. - */ - eProsima_user_DllExport NavSatFix( - const NavSatFix& x); - - /*! - * @brief Move constructor. - * @param x Reference to the object sensor_msgs::msg::NavSatFix that will be copied. - */ - eProsima_user_DllExport NavSatFix( - NavSatFix&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object sensor_msgs::msg::NavSatFix that will be copied. - */ - eProsima_user_DllExport NavSatFix& operator =( - const NavSatFix& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object sensor_msgs::msg::NavSatFix that will be copied. - */ - eProsima_user_DllExport NavSatFix& operator =( - NavSatFix&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x sensor_msgs::msg::NavSatFix object to compare. - */ - eProsima_user_DllExport bool operator ==( - const NavSatFix& x) const; - - /*! - * @brief Comparison operator. - * @param x sensor_msgs::msg::NavSatFix object to compare. - */ - eProsima_user_DllExport bool operator !=( - const NavSatFix& x) const; - - /*! - * @brief This function copies the value in member header - * @param _header New value to be copied in member header - */ - eProsima_user_DllExport void header( - const std_msgs::msg::Header& _header); - - /*! - * @brief This function moves the value in member header - * @param _header New value to be moved in member header - */ - eProsima_user_DllExport void header( - std_msgs::msg::Header&& _header); - - /*! - * @brief This function returns a constant reference to member header - * @return Constant reference to member header - */ - eProsima_user_DllExport const std_msgs::msg::Header& header() const; - - /*! - * @brief This function returns a reference to member header - * @return Reference to member header - */ - eProsima_user_DllExport std_msgs::msg::Header& header(); - /*! - * @brief This function copies the value in member status - * @param _status New value to be copied in member status - */ - eProsima_user_DllExport void status( - const sensor_msgs::msg::NavSatStatus& _status); - - /*! - * @brief This function moves the value in member status - * @param _status New value to be moved in member status - */ - eProsima_user_DllExport void status( - sensor_msgs::msg::NavSatStatus&& _status); - - /*! - * @brief This function returns a constant reference to member status - * @return Constant reference to member status - */ - eProsima_user_DllExport const sensor_msgs::msg::NavSatStatus& status() const; - - /*! - * @brief This function returns a reference to member status - * @return Reference to member status - */ - eProsima_user_DllExport sensor_msgs::msg::NavSatStatus& status(); - /*! - * @brief This function sets a value in member latitude - * @param _latitude New value for member latitude - */ - eProsima_user_DllExport void latitude( - double _latitude); - - /*! - * @brief This function returns the value of member latitude - * @return Value of member latitude - */ - eProsima_user_DllExport double latitude() const; - - /*! - * @brief This function returns a reference to member latitude - * @return Reference to member latitude - */ - eProsima_user_DllExport double& latitude(); - - /*! - * @brief This function sets a value in member longitude - * @param _longitude New value for member longitude - */ - eProsima_user_DllExport void longitude( - double _longitude); - - /*! - * @brief This function returns the value of member longitude - * @return Value of member longitude - */ - eProsima_user_DllExport double longitude() const; - - /*! - * @brief This function returns a reference to member longitude - * @return Reference to member longitude - */ - eProsima_user_DllExport double& longitude(); - - /*! - * @brief This function sets a value in member altitude - * @param _altitude New value for member altitude - */ - eProsima_user_DllExport void altitude( - double _altitude); - - /*! - * @brief This function returns the value of member altitude - * @return Value of member altitude - */ - eProsima_user_DllExport double altitude() const; - - /*! - * @brief This function returns a reference to member altitude - * @return Reference to member altitude - */ - eProsima_user_DllExport double& altitude(); - - /*! - * @brief This function copies the value in member position_covariance - * @param _position_covariance New value to be copied in member position_covariance - */ - eProsima_user_DllExport void position_covariance( - const sensor_msgs::msg::sensor_msgs__NavSatFix__double_array_9& _position_covariance); - - /*! - * @brief This function moves the value in member position_covariance - * @param _position_covariance New value to be moved in member position_covariance - */ - eProsima_user_DllExport void position_covariance( - sensor_msgs::msg::sensor_msgs__NavSatFix__double_array_9&& _position_covariance); - - /*! - * @brief This function returns a constant reference to member position_covariance - * @return Constant reference to member position_covariance - */ - eProsima_user_DllExport const sensor_msgs::msg::sensor_msgs__NavSatFix__double_array_9& position_covariance() const; - - /*! - * @brief This function returns a reference to member position_covariance - * @return Reference to member position_covariance - */ - eProsima_user_DllExport sensor_msgs::msg::sensor_msgs__NavSatFix__double_array_9& position_covariance(); - /*! - * @brief This function sets a value in member position_covariance_type - * @param _position_covariance_type New value for member position_covariance_type - */ - eProsima_user_DllExport void position_covariance_type( - uint8_t _position_covariance_type); - - /*! - * @brief This function returns the value of member position_covariance_type - * @return Value of member position_covariance_type - */ - eProsima_user_DllExport uint8_t position_covariance_type() const; - - /*! - * @brief This function returns a reference to member position_covariance_type - * @return Reference to member position_covariance_type - */ - eProsima_user_DllExport uint8_t& position_covariance_type(); - - /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ - eProsima_user_DllExport static size_t getMaxCdrSerializedSize( - size_t current_alignment = 0); - - /*! - * @brief This function returns the serialized size of a data depending on the buffer alignment. - * @param data Data which is calculated its serialized size. - * @param current_alignment Buffer alignment. - * @return Serialized size. - */ - eProsima_user_DllExport static size_t getCdrSerializedSize( - const sensor_msgs::msg::NavSatFix& data, - size_t current_alignment = 0); - - /*! - * @brief This function serializes an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& cdr) const; - - /*! - * @brief This function deserializes an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr); - - /*! - * @brief This function returns the maximum serialized size of the Key of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ - eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( - size_t current_alignment = 0); - - /*! - * @brief This function tells you if the Key has been defined for this type - */ - eProsima_user_DllExport static bool isKeyDefined(); - - /*! - * @brief This function serializes the key members of an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void serializeKey( - eprosima::fastcdr::Cdr& cdr) const; - - private: - std_msgs::msg::Header m_header; - sensor_msgs::msg::NavSatStatus m_status; - double m_latitude; - double m_longitude; - double m_altitude; - sensor_msgs::msg::sensor_msgs__NavSatFix__double_array_9 m_position_covariance; - uint8_t m_position_covariance_type; - }; - } // namespace msg -} // namespace sensor_msgs - -#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIX_H_ diff --git a/LibCarla/source/carla/ros2/types/NavSatStatusPubSubTypes.h b/LibCarla/source/carla/ros2/types/NavSatStatusPubSubTypes.h deleted file mode 100644 index 6abf09210de..00000000000 --- a/LibCarla/source/carla/ros2/types/NavSatStatusPubSubTypes.h +++ /dev/null @@ -1,138 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// 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. - -/*! - * @file NavSatStatusPubSubTypes.h - * This header file contains the declaration of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUS_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUS_PUBSUBTYPES_H_ - -#include -#include - -#include "NavSatStatus.h" - -#if !defined(GEN_API_VER) || (GEN_API_VER != 1) -#error \ - Generated NavSatStatus is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. -#endif // GEN_API_VER - -namespace sensor_msgs -{ - namespace msg - { - #ifndef SWIG - namespace detail { - - template - struct NavSatStatus_rob - { - friend constexpr typename Tag::type get( - Tag) - { - return M; - } - }; - - struct NavSatStatus_f - { - typedef uint16_t NavSatStatus::* type; - friend constexpr type get( - NavSatStatus_f); - }; - - template struct NavSatStatus_rob; - - template - inline size_t constexpr NavSatStatus_offset_of() { - return ((::size_t) &reinterpret_cast((((T*)0)->*get(Tag())))); - } - } - #endif - - /*! - * @brief This class represents the TopicDataType of the type NavSatStatus defined by the user in the IDL file. - * @ingroup NAVSATSTATUS - */ - class NavSatStatusPubSubType : public eprosima::fastdds::dds::TopicDataType - { - public: - - typedef NavSatStatus type; - - eProsima_user_DllExport NavSatStatusPubSubType(); - - eProsima_user_DllExport virtual ~NavSatStatusPubSubType() override; - - eProsima_user_DllExport virtual bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; - - eProsima_user_DllExport virtual bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, - void* data) override; - - eProsima_user_DllExport virtual std::function getSerializedSizeProvider( - void* data) override; - - eProsima_user_DllExport virtual bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport virtual void* createData() override; - - eProsima_user_DllExport virtual void deleteData( - void* data) override; - - #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return true; - } - - #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - - #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return is_plain_impl(); - } - - #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - new (memory) NavSatStatus(); - return true; - } - - #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; - unsigned char* m_keyBuffer; - private: - static constexpr bool is_plain_impl() - { - return 4ULL == (detail::NavSatStatus_offset_of() + sizeof(uint16_t)); - }}; - } -} - -#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUS_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/Object.h b/LibCarla/source/carla/ros2/types/Object.h new file mode 100644 index 00000000000..2072bc5b94d --- /dev/null +++ b/LibCarla/source/carla/ros2/types/Object.h @@ -0,0 +1,223 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include + +#include "carla/geom/BoundingBox.h" +#include "carla/ros2/types/AcceleratedMovement.h" +#include "carla/ros2/types/Polygon.h" +#include "carla/ros2/types/Timestamp.h" +#include "carla/ros2/types/TrafficLightActorDefinition.h" +#include "carla/ros2/types/TrafficSignActorDefinition.h" +#include "carla/ros2/types/Transform.h" +#include "carla/ros2/types/VehicleActorDefinition.h" +#include "carla/ros2/types/WalkerActorDefinition.h" +#include "carla/rpc/VehiclePhysicsControl.h" +#include "carla/sensor/data/ActorDynamicState.h" +#include "derived_object_msgs/msg/Object.h" +#include "derived_object_msgs/msg/ObjectWithCovariance.h" + +namespace carla { +namespace ros2 { +namespace types { + +/** + Convert a carla (linear) acceleration to a ROS accel (linear part) + + Considers the conversion from left-handed system (unreal) to right-handed + system (ROS) +*/ +class Object { +public: + /** + * The representation of an object in the sense of derived_object_msgs::msg::Object. + * + * classification is one of the derived_object_msgs::msg::Object_Constants::CLASSIFICATION_* constants + */ + explicit Object(std::shared_ptr vehicle_actor_definition) + : _actor_name_definition( + std::static_pointer_cast(vehicle_actor_definition)) { + if (_actor_name_definition->base_type == "Bus" || _actor_name_definition->base_type == "Truck") { + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_TRUCK; + } else if (_actor_name_definition->base_type == "car" || _actor_name_definition->base_type == "van") { + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_CAR; + } else if (_actor_name_definition->base_type == "motorcycle") { + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_MOTORCYCLE; + } else if (_actor_name_definition->base_type == "bicycle") { + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_BIKE; + } else { + // as long as we don't have the concrete information within a blueprint ... + // we estimate the class based on the vehicle mass (motorbikes are also 4wheeled vehicles!) + if (vehicle_actor_definition->vehicle_physics_control.mass > 2000.f) { + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_TRUCK; + } + /* microlino has 513kg */ + else if (vehicle_actor_definition->vehicle_physics_control.mass > 500.f) { + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_CAR; + } + /* gazelle bike has 150 (ok, when 130kg person is sitting on it ;-), but yamaha 140kg how should that work out?? + TODO: update Blueprint masses to more realistic values */ + else if (vehicle_actor_definition->vehicle_physics_control.mass > 100.f) { + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_MOTORCYCLE; + } else { + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_BIKE; + } + carla::log_warning( + "Unknown Vehicle Object[", _actor_name_definition->type_id, "] id: ", _actor_name_definition->id, + " object_type: ", _actor_name_definition->object_type, " base_type: ", _actor_name_definition->base_type, + " mass: ", vehicle_actor_definition->vehicle_physics_control.mass, " ROS-class: ", _classification); + } + } + /** + * The representation of an object in the sense of derived_object_msgs::msg::Object. + * + * classification is one of the derived_object_msgs::msg::Object_Constants::CLASSIFICATION_* constants + */ + explicit Object(std::shared_ptr walker_actor_definition) + : _actor_name_definition( + std::static_pointer_cast(walker_actor_definition)) { + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_PEDESTRIAN; + carla::log_info("Creating Walker Object[", _actor_name_definition->type_id, "] id: ", _actor_name_definition->id, + " object_type: ", _actor_name_definition->object_type, + " base_type: ", _actor_name_definition->base_type, " ROS-class: ", _classification); + } + /** + * The representation of an object in the sense of derived_object_msgs::msg::Object. + * + * classification is one of the derived_object_msgs::msg::Object_Constants::CLASSIFICATION_* constants + */ + explicit Object(std::shared_ptr traffic_light_actor_definition) + : _actor_name_definition( + std::static_pointer_cast(traffic_light_actor_definition)) { + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_SIGN; + carla::log_info("Creating Traffic Light Object[", _actor_name_definition->type_id, + "] id: ", _actor_name_definition->id, " object_type: ", _actor_name_definition->object_type, + " base_type: ", _actor_name_definition->base_type, " ROS-class: ", _classification); + } + /** + * The representation of an object in the sense of derived_object_msgs::msg::Object. + * + * classification is one of the derived_object_msgs::msg::Object_Constants::CLASSIFICATION_* constants + */ + explicit Object(std::shared_ptr traffic_sign_actor_definition) + : _actor_name_definition( + std::static_pointer_cast(traffic_sign_actor_definition)) { + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_SIGN; + carla::log_info("Creating Traffic Sign Object[", _actor_name_definition->type_id, + "] id: ", _actor_name_definition->id, " object_type: ", _actor_name_definition->object_type, + " base_type: ", _actor_name_definition->base_type, " ROS-class: ", _classification); + } + ~Object() = default; + Object(const Object&) = delete; + Object& operator=(const Object&) = delete; + Object(Object&&) = delete; + Object& operator=(Object&&) = delete; + + void UpdateObject(carla::ros2::types::Timestamp const& timestamp, + carla::sensor::data::ActorDynamicState const& actor_dynamic_state) { + auto actor_definition = std::dynamic_pointer_cast(_actor_name_definition); + if (nullptr != actor_definition) { + _bounding_box.extent = actor_definition->bounding_box.extent; + _bounding_box.location = actor_dynamic_state.transform.location; + _bounding_box.rotation = actor_dynamic_state.transform.rotation; + } + _transform = carla::ros2::types::Transform(actor_dynamic_state.transform, actor_dynamic_state.quaternion); + _accelerated_movement.UpdateSpeed( + carla::ros2::types::Speed(carla::geom::Velocity(actor_dynamic_state.velocity), actor_dynamic_state.quaternion), + carla::ros2::types::AngularVelocity(carla::geom::AngularVelocity(actor_dynamic_state.angular_velocity)), + timestamp); + if (_classification_age < std::numeric_limits::max()) { + ++_classification_age; + } + } + + derived_object_msgs::msg::Object object() const { + derived_object_msgs::msg::Object object; + object.header().stamp(_accelerated_movement.Timestamp().time()); + object.header().frame_id("map"); + object.id(_actor_name_definition->id); + object.detection_level(derived_object_msgs::msg::Object_Constants::OBJECT_TRACKED); + object.object_classified(true); + object.pose(_transform.pose()); + object.twist(_accelerated_movement.twist()); + object.accel(_accelerated_movement.accel()); + + auto actor_definition = std::dynamic_pointer_cast(_actor_name_definition); + if (nullptr != actor_definition) { + object.shape().type(shape_msgs::msg::SolidPrimitive_Constants::BOX); + auto const ros_extent = _bounding_box.extent * 2.f; + object.shape().dimensions({ros_extent.x, ros_extent.y, ros_extent.z}); + object.shape().polygon().points(*Polygon(_bounding_box.GetLocalVertices()).polygon()); + } else { + object.shape().type(shape_msgs::msg::SolidPrimitive_Constants::BOX_X); + } + object.classification(_classification); + object.classification_certainty(255u); + object.classification_age(_classification_age); + return object; + } + + derived_object_msgs::msg::ObjectWithCovariance object_with_covariance() const { + derived_object_msgs::msg::ObjectWithCovariance object; + object.header().stamp(_accelerated_movement.Timestamp().time()); + object.header().frame_id("map"); + object.id(_actor_name_definition->id); + object.detection_level(derived_object_msgs::msg::Object_Constants::OBJECT_TRACKED); + object.object_classified(true); + object.pose(_transform.pose_with_covariance()); + object.twist(_accelerated_movement.twist_with_covariance()); + object.accel(_accelerated_movement.accel_with_covariance()); + + auto actor_definition = std::dynamic_pointer_cast(_actor_name_definition); + if (nullptr != actor_definition) { + object.shape().type(shape_msgs::msg::SolidPrimitive_Constants::BOX); + auto const ros_extent = _bounding_box.extent * 2.f; + object.shape().dimensions({ros_extent.x, ros_extent.y, ros_extent.z}); + //object.shape().polygon().points(*Polygon(_bounding_box.GetLocalVertices()).polygon()); + } else { + object.shape().type(shape_msgs::msg::SolidPrimitive_Constants::BOX_X); + } + object.classification(_classification); + object.classification_certainty(255u); + object.classification_age(_classification_age); + return object; + } + + carla::ros2::types::Timestamp const& Timestamp() const { + return _accelerated_movement.Timestamp(); + } + carla::ros2::types::Transform const& Transform() const { + return _transform; + } + carla::ros2::types::Speed const& Speed() const { + return _accelerated_movement.Speed(); + } + carla::ros2::types::AngularVelocity const& AngularVelocity() const { + return _accelerated_movement.AngularVelocity(); + } + carla::ros2::types::AcceleratedMovement const& AcceleratedMovement() const { + return _accelerated_movement; + } + + uint8_t classification() { + return _classification; + } + + carla_msgs::msg::CarlaActorInfo carla_actor_info(std::shared_ptr name_registry) const { + return _actor_name_definition->carla_actor_info(name_registry); + } + +private: + std::shared_ptr _actor_name_definition; + uint8_t _classification; + carla::geom::BoundingBox _bounding_box; + carla::ros2::types::Transform _transform; + carla::ros2::types::AcceleratedMovement _accelerated_movement; + uint32_t _classification_age{0u}; +}; +} // namespace types +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/PointCloud2.cpp b/LibCarla/source/carla/ros2/types/PointCloud2.cpp deleted file mode 100644 index e89c0412f70..00000000000 --- a/LibCarla/source/carla/ros2/types/PointCloud2.cpp +++ /dev/null @@ -1,507 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// 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. - -/*! - * @file PointCloud2.cpp - * This source file contains the definition of the described types in the IDL file. - * - * This file was generated by the tool gen. - */ - -#ifdef _WIN32 -// Remove linker warning LNK4221 on Visual Studio -namespace { -char dummy; -} // namespace -#endif // _WIN32 - -#include "PointCloud2.h" -#include - -#include -using namespace eprosima::fastcdr::exception; - -#include - -#define sensor_msgs_msg_PointField_max_cdr_typesize 272ULL; -#define std_msgs_msg_Time_max_cdr_typesize 8ULL; -#define sensor_msgs_msg_PointCloud2_max_cdr_typesize 27597ULL; -#define std_msgs_msg_Header_max_cdr_typesize 268ULL; -#define sensor_msgs_msg_PointField_max_key_cdr_typesize 0ULL; -#define std_msgs_msg_Time_max_key_cdr_typesize 0ULL; -#define sensor_msgs_msg_PointCloud2_max_key_cdr_typesize 0ULL; -#define std_msgs_msg_Header_max_key_cdr_typesize 0ULL; - -sensor_msgs::msg::PointCloud2::PointCloud2() -{ - // std_msgs::msg::Header m_header - - // unsigned long m_height - m_height = 0; - // unsigned long m_width - m_width = 0; - // sequence m_fields - - // boolean m_is_bigendian - m_is_bigendian = false; - // unsigned long m_point_step - m_point_step = 0; - // unsigned long m_row_step - m_row_step = 0; - // sequence m_data - - // boolean m_is_dense - m_is_dense = false; -} - -sensor_msgs::msg::PointCloud2::~PointCloud2() -{ -} - -sensor_msgs::msg::PointCloud2::PointCloud2( - const PointCloud2& x) -{ - m_header = x.m_header; - m_height = x.m_height; - m_width = x.m_width; - m_fields = x.m_fields; - m_is_bigendian = x.m_is_bigendian; - m_point_step = x.m_point_step; - m_row_step = x.m_row_step; - m_data = x.m_data; - m_is_dense = x.m_is_dense; -} - -sensor_msgs::msg::PointCloud2::PointCloud2( - PointCloud2&& x) noexcept -{ - m_header = std::move(x.m_header); - m_height = x.m_height; - m_width = x.m_width; - m_fields = std::move(x.m_fields); - m_is_bigendian = x.m_is_bigendian; - m_point_step = x.m_point_step; - m_row_step = x.m_row_step; - m_data = std::move(x.m_data); - m_is_dense = x.m_is_dense; -} - -sensor_msgs::msg::PointCloud2& sensor_msgs::msg::PointCloud2::operator =( - const PointCloud2& x) -{ - m_header = x.m_header; - m_height = x.m_height; - m_width = x.m_width; - m_fields = x.m_fields; - m_is_bigendian = x.m_is_bigendian; - m_point_step = x.m_point_step; - m_row_step = x.m_row_step; - m_data = x.m_data; - m_is_dense = x.m_is_dense; - - return *this; -} - -sensor_msgs::msg::PointCloud2& sensor_msgs::msg::PointCloud2::operator =( - PointCloud2&& x) noexcept -{ - m_header = std::move(x.m_header); - m_height = x.m_height; - m_width = x.m_width; - m_fields = std::move(x.m_fields); - m_is_bigendian = x.m_is_bigendian; - m_point_step = x.m_point_step; - m_row_step = x.m_row_step; - m_data = std::move(x.m_data); - m_is_dense = x.m_is_dense; - - return *this; -} - -bool sensor_msgs::msg::PointCloud2::operator ==( - const PointCloud2& x) const -{ - return (m_header == x.m_header && m_height == x.m_height && m_width == x.m_width && m_fields == x.m_fields && m_is_bigendian == x.m_is_bigendian && m_point_step == x.m_point_step && m_row_step == x.m_row_step && m_data == x.m_data && m_is_dense == x.m_is_dense); -} - -bool sensor_msgs::msg::PointCloud2::operator !=( - const PointCloud2& x) const -{ - return !(*this == x); -} - -size_t sensor_msgs::msg::PointCloud2::getMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return sensor_msgs_msg_PointCloud2_max_cdr_typesize; -} - -size_t sensor_msgs::msg::PointCloud2::getCdrSerializedSize( - const sensor_msgs::msg::PointCloud2& data, - size_t current_alignment) -{ - size_t initial_alignment = current_alignment; - current_alignment += std_msgs::msg::Header::getCdrSerializedSize(data.header(), current_alignment); - current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); - current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); - current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); - - for(size_t a = 0; a < data.fields().size(); ++a) - { - current_alignment += sensor_msgs::msg::PointField::getCdrSerializedSize(data.fields().at(a), current_alignment); - } - - current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); - current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); - current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); - current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); - - if (data.data().size() > 0) - { - current_alignment += (data.data().size() * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); - } - - current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); - - return current_alignment - initial_alignment; -} - -void sensor_msgs::msg::PointCloud2::serialize( - eprosima::fastcdr::Cdr& scdr) const -{ - scdr << m_header; - scdr << m_height; - scdr << m_width; - scdr << m_fields; - scdr << m_is_bigendian; - scdr << m_point_step; - scdr << m_row_step; - scdr << m_data; - scdr << m_is_dense; -} - -void sensor_msgs::msg::PointCloud2::deserialize( - eprosima::fastcdr::Cdr& dcdr) -{ - dcdr >> m_header; - dcdr >> m_height; - dcdr >> m_width; - dcdr >> m_fields; - dcdr >> m_is_bigendian; - dcdr >> m_point_step; - dcdr >> m_row_step; - dcdr >> m_data; - dcdr >> m_is_dense; -} - -/*! - * @brief This function copies the value in member header - * @param _header New value to be copied in member header - */ -void sensor_msgs::msg::PointCloud2::header( - const std_msgs::msg::Header& _header) -{ - m_header = _header; -} - -/*! - * @brief This function moves the value in member header - * @param _header New value to be moved in member header - */ -void sensor_msgs::msg::PointCloud2::header( - std_msgs::msg::Header&& _header) -{ - m_header = std::move(_header); -} - -/*! - * @brief This function returns a constant reference to member header - * @return Constant reference to member header - */ -const std_msgs::msg::Header& sensor_msgs::msg::PointCloud2::header() const -{ - return m_header; -} - -/*! - * @brief This function returns a reference to member header - * @return Reference to member header - */ -std_msgs::msg::Header& sensor_msgs::msg::PointCloud2::header() -{ - return m_header; -} - -/*! - * @brief This function sets a value in member height - * @param _height New value for member height - */ -void sensor_msgs::msg::PointCloud2::height( - uint32_t _height) -{ - m_height = _height; -} - -/*! - * @brief This function returns the value of member height - * @return Value of member height - */ -uint32_t sensor_msgs::msg::PointCloud2::height() const -{ - return m_height; -} - -/*! - * @brief This function returns a reference to member height - * @return Reference to member height - */ -uint32_t& sensor_msgs::msg::PointCloud2::height() -{ - return m_height; -} - -/*! - * @brief This function sets a value in member width - * @param _width New value for member width - */ -void sensor_msgs::msg::PointCloud2::width( - uint32_t _width) -{ - m_width = _width; -} - -/*! - * @brief This function returns the value of member width - * @return Value of member width - */ -uint32_t sensor_msgs::msg::PointCloud2::width() const -{ - return m_width; -} - -/*! - * @brief This function returns a reference to member width - * @return Reference to member width - */ -uint32_t& sensor_msgs::msg::PointCloud2::width() -{ - return m_width; -} - -/*! - * @brief This function copies the value in member fields - * @param _fields New value to be copied in member fields - */ -void sensor_msgs::msg::PointCloud2::fields( - const std::vector& _fields) -{ - m_fields = _fields; -} - -/*! - * @brief This function moves the value in member fields - * @param _fields New value to be moved in member fields - */ -void sensor_msgs::msg::PointCloud2::fields( - std::vector&& _fields) -{ - m_fields = std::move(_fields); -} - -/*! - * @brief This function returns a constant reference to member fields - * @return Constant reference to member fields - */ -const std::vector& sensor_msgs::msg::PointCloud2::fields() const -{ - return m_fields; -} - -/*! - * @brief This function returns a reference to member fields - * @return Reference to member fields - */ -std::vector& sensor_msgs::msg::PointCloud2::fields() -{ - return m_fields; -} - -/*! - * @brief This function sets a value in member is_bigendian - * @param _is_bigendian New value for member is_bigendian - */ -void sensor_msgs::msg::PointCloud2::is_bigendian( - bool _is_bigendian) -{ - m_is_bigendian = _is_bigendian; -} - -/*! - * @brief This function returns the value of member is_bigendian - * @return Value of member is_bigendian - */ -bool sensor_msgs::msg::PointCloud2::is_bigendian() const -{ - return m_is_bigendian; -} - -/*! - * @brief This function returns a reference to member is_bigendian - * @return Reference to member is_bigendian - */ -bool& sensor_msgs::msg::PointCloud2::is_bigendian() -{ - return m_is_bigendian; -} - -/*! - * @brief This function sets a value in member point_step - * @param _point_step New value for member point_step - */ -void sensor_msgs::msg::PointCloud2::point_step( - uint32_t _point_step) -{ - m_point_step = _point_step; -} - -/*! - * @brief This function returns the value of member point_step - * @return Value of member point_step - */ -uint32_t sensor_msgs::msg::PointCloud2::point_step() const -{ - return m_point_step; -} - -/*! - * @brief This function returns a reference to member point_step - * @return Reference to member point_step - */ -uint32_t& sensor_msgs::msg::PointCloud2::point_step() -{ - return m_point_step; -} - -/*! - * @brief This function sets a value in member row_step - * @param _row_step New value for member row_step - */ -void sensor_msgs::msg::PointCloud2::row_step( - uint32_t _row_step) -{ - m_row_step = _row_step; -} - -/*! - * @brief This function returns the value of member row_step - * @return Value of member row_step - */ -uint32_t sensor_msgs::msg::PointCloud2::row_step() const -{ - return m_row_step; -} - -/*! - * @brief This function returns a reference to member row_step - * @return Reference to member row_step - */ -uint32_t& sensor_msgs::msg::PointCloud2::row_step() -{ - return m_row_step; -} - -/*! - * @brief This function copies the value in member data - * @param _data New value to be copied in member data - */ -void sensor_msgs::msg::PointCloud2::data( - const std::vector& _data) -{ - m_data = _data; -} - -/*! - * @brief This function moves the value in member data - * @param _data New value to be moved in member data - */ -void sensor_msgs::msg::PointCloud2::data( - std::vector&& _data) -{ - m_data = std::move(_data); -} - -/*! - * @brief This function returns a constant reference to member data - * @return Constant reference to member data - */ -const std::vector& sensor_msgs::msg::PointCloud2::data() const -{ - return m_data; -} - -/*! - * @brief This function returns a reference to member data - * @return Reference to member data - */ -std::vector& sensor_msgs::msg::PointCloud2::data() -{ - return m_data; -} - -/*! - * @brief This function sets a value in member is_dense - * @param _is_dense New value for member is_dense - */ -void sensor_msgs::msg::PointCloud2::is_dense( - bool _is_dense) -{ - m_is_dense = _is_dense; -} - -/*! - * @brief This function returns the value of member is_dense - * @return Value of member is_dense - */ -bool sensor_msgs::msg::PointCloud2::is_dense() const -{ - return m_is_dense; -} - -/*! - * @brief This function returns a reference to member is_dense - * @return Reference to member is_dense - */ -bool& sensor_msgs::msg::PointCloud2::is_dense() -{ - return m_is_dense; -} - -size_t sensor_msgs::msg::PointCloud2::getKeyMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return sensor_msgs_msg_PointCloud2_max_key_cdr_typesize; -} - -bool sensor_msgs::msg::PointCloud2::isKeyDefined() -{ - return false; -} - -void sensor_msgs::msg::PointCloud2::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} diff --git a/LibCarla/source/carla/ros2/types/Polygon.h b/LibCarla/source/carla/ros2/types/Polygon.h new file mode 100644 index 00000000000..8f26ec0fca9 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/Polygon.h @@ -0,0 +1,66 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include +#include + +#include "carla/geom/Location.h" +#include "carla/ros2/types/CoordinateSystemTransform.h" +#include "geometry_msgs/msg/Point32.h" + +namespace carla { +namespace ros2 { +namespace types { + +/** + Convert a carla (linear) acceleration to a ROS accel (linear part) + + Considers the conversion from left-handed system (unreal) to right-handed + system (ROS) +*/ +class Polygon { +public: + /** + * The representation of an (dynamic) Polygon in the sense of derived_Polygon_msgs::msg::Polygon. + * + * classification is one of the derived_Polygon_msgs::msg::Polygon_Constants::CLASSIFICATION_* constants + */ + Polygon(std::array const &vertices) + : _ros_polygon(std::make_shared>()) { + _ros_polygon->reserve(vertices.size()); + for (auto const &vertex : vertices) { + _ros_polygon->push_back(CoordinateSystemTransform::TransformLocationToPoint32Msg(vertex)); + } + } +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + Polygon() : _ros_polygon(std::make_shared>()) {} + void SetGlobalVertices(TArray const &vertices) { + _ros_polygon->reserve(vertices.Num()); + for (auto const &vertex : vertices) { + _ros_polygon->push_back(CoordinateSystemTransform::TransformLocationToPoint32Msg(carla::geom::Location(vertex))); + } + } +#endif // LIBCARLA_INCLUDED_FROM_UE4 + + ~Polygon() = default; + Polygon(const Polygon &) = default; + Polygon &operator=(const Polygon &) = default; + Polygon(Polygon &&) = default; + Polygon &operator=(Polygon &&) = default; + + std::shared_ptr> polygon() const { + return _ros_polygon; + } + +private: + // store a shared_ptr to prevent from vector copies + std::shared_ptr> _ros_polygon; +}; + +} // namespace types +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/PosePubSubTypes.h b/LibCarla/source/carla/ros2/types/PosePubSubTypes.h deleted file mode 100644 index 6c19d63db60..00000000000 --- a/LibCarla/source/carla/ros2/types/PosePubSubTypes.h +++ /dev/null @@ -1,142 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// 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. - -/*! - * @file PosePubSubTypes.h - * This header file contains the declaration of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSE_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSE_PUBSUBTYPES_H_ - -#include -#include - -#include "Pose.h" - -#include "PointPubSubTypes.h" -#include "QuaternionPubSubTypes.h" - -#if !defined(GEN_API_VER) || (GEN_API_VER != 1) -#error \ - Generated Pose is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. -#endif // GEN_API_VER - -namespace geometry_msgs -{ - namespace msg - { - #ifndef SWIG - namespace detail { - - template - struct Pose_rob - { - friend constexpr typename Tag::type get( - Tag) - { - return M; - } - }; - - struct Pose_f - { - typedef geometry_msgs::msg::Quaternion Pose::* type; - friend constexpr type get( - Pose_f); - }; - - template struct Pose_rob; - - template - inline size_t constexpr Pose_offset_of() { - return ((::size_t) &reinterpret_cast((((T*)0)->*get(Tag())))); - } - } - #endif - - /*! - * @brief This class represents the TopicDataType of the type Pose defined by the user in the IDL file. - * @ingroup POSE - */ - class PosePubSubType : public eprosima::fastdds::dds::TopicDataType - { - public: - - typedef Pose type; - - eProsima_user_DllExport PosePubSubType(); - - eProsima_user_DllExport virtual ~PosePubSubType() override; - - eProsima_user_DllExport virtual bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; - - eProsima_user_DllExport virtual bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, - void* data) override; - - eProsima_user_DllExport virtual std::function getSerializedSizeProvider( - void* data) override; - - eProsima_user_DllExport virtual bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport virtual void* createData() override; - - eProsima_user_DllExport virtual void deleteData( - void* data) override; - - #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return true; - } - - #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - - #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return is_plain_impl(); - } - - #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - new (memory) Pose(); - return true; - } - - #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; - unsigned char* m_keyBuffer; - private: - static constexpr bool is_plain_impl() - { - return 56ULL == (detail::Pose_offset_of() + sizeof(geometry_msgs::msg::Quaternion)); - - }}; - } -} - -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSE_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/PoseWithCovariancePubSubTypes.h b/LibCarla/source/carla/ros2/types/PoseWithCovariancePubSubTypes.h deleted file mode 100644 index ee02471c2a9..00000000000 --- a/LibCarla/source/carla/ros2/types/PoseWithCovariancePubSubTypes.h +++ /dev/null @@ -1,142 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// 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. - -/*! - * @file PoseWithCovariancePubSubTypes.h - * This header file contains the declaration of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCE_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCE_PUBSUBTYPES_H_ - -#include -#include - -#include "PoseWithCovariance.h" -#include "PosePubSubTypes.h" - -#if !defined(GEN_API_VER) || (GEN_API_VER != 1) -#error \ - Generated PoseWithCovariance is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. -#endif // GEN_API_VER - -namespace geometry_msgs -{ - namespace msg - { - typedef std::array geometry_msgs__PoseWithCovariance__double_array_36; - - #ifndef SWIG - namespace detail { - - template - struct PoseWithCovariance_rob - { - friend constexpr typename Tag::type get( - Tag) - { - return M; - } - }; - - struct PoseWithCovariance_f - { - typedef geometry_msgs::msg::geometry_msgs__PoseWithCovariance__double_array_36 PoseWithCovariance::* type; - friend constexpr type get( - PoseWithCovariance_f); - }; - - template struct PoseWithCovariance_rob; - - template - inline size_t constexpr PoseWithCovariance_offset_of() { - return ((::size_t) &reinterpret_cast((((T*)0)->*get(Tag())))); - } - } - #endif - - /*! - * @brief This class represents the TopicDataType of the type PoseWithCovariance defined by the user in the IDL file. - * @ingroup POSEWITHCOVARIANCE - */ - class PoseWithCovariancePubSubType : public eprosima::fastdds::dds::TopicDataType - { - public: - - typedef PoseWithCovariance type; - - eProsima_user_DllExport PoseWithCovariancePubSubType(); - - eProsima_user_DllExport virtual ~PoseWithCovariancePubSubType() override; - - eProsima_user_DllExport virtual bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; - - eProsima_user_DllExport virtual bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, - void* data) override; - - eProsima_user_DllExport virtual std::function getSerializedSizeProvider( - void* data) override; - - eProsima_user_DllExport virtual bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport virtual void* createData() override; - - eProsima_user_DllExport virtual void deleteData( - void* data) override; - - #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return true; - } - - #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - - #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return is_plain_impl(); - } - - #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - new (memory) PoseWithCovariance(); - return true; - } - - #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; - unsigned char* m_keyBuffer; - private: - static constexpr bool is_plain_impl() - { - return 344ULL == (detail::PoseWithCovariance_offset_of() + sizeof(geometry_msgs::msg::geometry_msgs__PoseWithCovariance__double_array_36)); - - }}; - } -} - -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCE_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/PublisherSensorType.h b/LibCarla/source/carla/ros2/types/PublisherSensorType.h new file mode 100644 index 00000000000..53624cf416a --- /dev/null +++ b/LibCarla/source/carla/ros2/types/PublisherSensorType.h @@ -0,0 +1,88 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +namespace carla { +namespace ros2 { +namespace types { + +enum class PublisherSensorType { + CollisionSensor, + DepthCamera, + NormalsCamera, + DVSCamera, + GnssSensor, + InertialMeasurementUnit, + LaneInvasionSensor, + ObstacleDetectionSensor, + OpticalFlowCamera, + Radar, + RayCastSemanticLidar, + RayCastLidar, + RssSensor, + SceneCaptureCamera, + SemanticSegmentationCamera, + InstanceSegmentationCamera, + WorldObserver, + CameraGBufferUint8, + CameraGBufferFloat, + V2X, + V2XCustom, + Unknown +}; +} +} // namespace ros2 +} // namespace carla + +namespace std { +inline std::string to_string(carla::ros2::types::PublisherSensorType sensor_type) { + switch (sensor_type) { + case carla::ros2::types::PublisherSensorType::CollisionSensor: + return "CollisionSensor"; + case carla::ros2::types::PublisherSensorType::DepthCamera: + return "DepthCamera"; + case carla::ros2::types::PublisherSensorType::NormalsCamera: + return "NormalsCamera"; + case carla::ros2::types::PublisherSensorType::DVSCamera: + return "DVSCamera"; + case carla::ros2::types::PublisherSensorType::GnssSensor: + return "GnssSensor"; + case carla::ros2::types::PublisherSensorType::InertialMeasurementUnit: + return "InertialMeasurementUnit"; + case carla::ros2::types::PublisherSensorType::LaneInvasionSensor: + return "LaneInvasionSensor"; + case carla::ros2::types::PublisherSensorType::ObstacleDetectionSensor: + return "ObstacleDetectionSensor"; + case carla::ros2::types::PublisherSensorType::OpticalFlowCamera: + return "OpticalFlowCamera"; + case carla::ros2::types::PublisherSensorType::Radar: + return "Radar"; + case carla::ros2::types::PublisherSensorType::RayCastSemanticLidar: + return "RayCastSemanticLidar"; + case carla::ros2::types::PublisherSensorType::RayCastLidar: + return "RayCastLidar"; + case carla::ros2::types::PublisherSensorType::RssSensor: + return "RssSensor"; + case carla::ros2::types::PublisherSensorType::SceneCaptureCamera: + return "SceneCaptureCamera"; + case carla::ros2::types::PublisherSensorType::SemanticSegmentationCamera: + return "SemanticSegmentationCamera"; + case carla::ros2::types::PublisherSensorType::InstanceSegmentationCamera: + return "InstanceSegmentationCamera"; + case carla::ros2::types::PublisherSensorType::WorldObserver: + return "WorldObserver"; + case carla::ros2::types::PublisherSensorType::CameraGBufferUint8: + return "CameraGBufferUint8"; + case carla::ros2::types::PublisherSensorType::CameraGBufferFloat: + return "CameraGBufferFloat"; + case carla::ros2::types::PublisherSensorType::V2X: + return "V2X"; + case carla::ros2::types::PublisherSensorType::V2XCustom: + return "V2XCustom"; + default: + return "Unknown"; + } +} +} // namespace std diff --git a/LibCarla/source/carla/ros2/types/Quaternion.h b/LibCarla/source/carla/ros2/types/Quaternion.h index 5e832eff1bd..7dbe50bc0f7 100644 --- a/LibCarla/source/carla/ros2/types/Quaternion.h +++ b/LibCarla/source/carla/ros2/types/Quaternion.h @@ -1,265 +1,69 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// 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. - -/*! - * @file Quaternion.h - * This header file contains the declaration of the described types in the IDL file. - * - * This file was generated by the tool gen. - */ - -#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNION_H_ -#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNION_H_ - -#include - -#include -#include -#include -#include -#include -#include - -#if defined(_WIN32) -#if defined(EPROSIMA_USER_DLL_EXPORT) -#define eProsima_user_DllExport __declspec( dllexport ) -#else -#define eProsima_user_DllExport -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define eProsima_user_DllExport -#endif // _WIN32 - -#if defined(_WIN32) -#if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(Quaternion_SOURCE) -#define Quaternion_DllAPI __declspec( dllexport ) -#else -#define Quaternion_DllAPI __declspec( dllimport ) -#endif // Quaternion_SOURCE -#else -#define Quaternion_DllAPI -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define Quaternion_DllAPI -#endif // _WIN32 - -namespace eprosima { -namespace fastcdr { -class Cdr; -} // namespace fastcdr -} // namespace eprosima - -namespace geometry_msgs { - namespace msg { - /*! - * @brief This class represents the structure Quaternion defined by the user in the IDL file. - * @ingroup QUATERNION - */ - class Quaternion - { - public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport Quaternion(); - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~Quaternion(); - - /*! - * @brief Copy constructor. - * @param x Reference to the object geometry_msgs::msg::Quaternion that will be copied. - */ - eProsima_user_DllExport Quaternion( - const Quaternion& x); - - /*! - * @brief Move constructor. - * @param x Reference to the object geometry_msgs::msg::Quaternion that will be copied. - */ - eProsima_user_DllExport Quaternion( - Quaternion&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object geometry_msgs::msg::Quaternion that will be copied. - */ - eProsima_user_DllExport Quaternion& operator =( - const Quaternion& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object geometry_msgs::msg::Quaternion that will be copied. - */ - eProsima_user_DllExport Quaternion& operator =( - Quaternion&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x geometry_msgs::msg::Quaternion object to compare. - */ - eProsima_user_DllExport bool operator ==( - const Quaternion& x) const; - - /*! - * @brief Comparison operator. - * @param x geometry_msgs::msg::Quaternion object to compare. - */ - eProsima_user_DllExport bool operator !=( - const Quaternion& x) const; - - /*! - * @brief This function sets a value in member x - * @param _x New value for member x - */ - eProsima_user_DllExport void x( - double _x); - - /*! - * @brief This function returns the value of member x - * @return Value of member x - */ - eProsima_user_DllExport double x() const; - - /*! - * @brief This function returns a reference to member x - * @return Reference to member x - */ - eProsima_user_DllExport double& x(); - - /*! - * @brief This function sets a value in member y - * @param _y New value for member y - */ - eProsima_user_DllExport void y( - double _y); - - /*! - * @brief This function returns the value of member y - * @return Value of member y - */ - eProsima_user_DllExport double y() const; - - /*! - * @brief This function returns a reference to member y - * @return Reference to member y - */ - eProsima_user_DllExport double& y(); - - /*! - * @brief This function sets a value in member z - * @param _z New value for member z - */ - eProsima_user_DllExport void z( - double _z); - - /*! - * @brief This function returns the value of member z - * @return Value of member z - */ - eProsima_user_DllExport double z() const; - - /*! - * @brief This function returns a reference to member z - * @return Reference to member z - */ - eProsima_user_DllExport double& z(); - - /*! - * @brief This function sets a value in member w - * @param _w New value for member w - */ - eProsima_user_DllExport void w( - double _w); - - /*! - * @brief This function returns the value of member w - * @return Value of member w - */ - eProsima_user_DllExport double w() const; - - /*! - * @brief This function returns a reference to member w - * @return Reference to member w - */ - eProsima_user_DllExport double& w(); - - /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ - eProsima_user_DllExport static size_t getMaxCdrSerializedSize( - size_t current_alignment = 0); - - /*! - * @brief This function returns the serialized size of a data depending on the buffer alignment. - * @param data Data which is calculated its serialized size. - * @param current_alignment Buffer alignment. - * @return Serialized size. - */ - eProsima_user_DllExport static size_t getCdrSerializedSize( - const geometry_msgs::msg::Quaternion& data, - size_t current_alignment = 0); - - /*! - * @brief This function serializes an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& cdr) const; - - /*! - * @brief This function deserializes an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr); - - /*! - * @brief This function returns the maximum serialized size of the Key of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ - eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( - size_t current_alignment = 0); - - /*! - * @brief This function tells you if the Key has been defined for this type - */ - eProsima_user_DllExport static bool isKeyDefined(); - - /*! - * @brief This function serializes the key members of an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void serializeKey( - eprosima::fastcdr::Cdr& cdr) const; - - private: - double m_x; - double m_y; - double m_z; - double m_w; - }; - } // namespace msg -} // namespace geometry_msgs - -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNION_H_ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/geom/Math.h" +#include "carla/geom/Quaternion.h" +#include "geometry_msgs/msg/Quaternion.h" + +namespace carla { +namespace ros2 { +namespace types { + +/** + Convert a carla rotation to a ROS quaternion + + Considers the conversion from left-handed system (unreal) to right-handed + system (ROS). + Considers the conversion from degrees (carla) to radians (ROS). +*/ +class Quaternion { +public: + /** + * carla_rotation: the carla Rotation + */ + explicit Quaternion(const geom::Quaternion& carla_quaternion) { + // left-handed to right-handed -> negate the rotation by negating all axis components + // switch y-axis from right to left -> negate y-axis + _ros_quaternion.x(-carla_quaternion.x); // -(forward = forward) + _ros_quaternion.y(carla_quaternion.y); // -( right = -left ) + _ros_quaternion.z(-carla_quaternion.z); // -( up = up ) + _ros_quaternion.w(carla_quaternion.w); + } + /** + * carla_rotation: the carla Rotation + */ + explicit Quaternion(const geometry_msgs::msg::Quaternion& ros_quaternion) : _ros_quaternion(ros_quaternion) {} + + ~Quaternion() = default; + Quaternion(const Quaternion&) = default; + Quaternion& operator=(const Quaternion&) = default; + Quaternion(Quaternion&&) = default; + Quaternion& operator=(Quaternion&&) = default; + + /** + * The resulting ROS geometry_msgs::msg::Quaternion + */ + geometry_msgs::msg::Quaternion quaternion() const { + return _ros_quaternion; + } + + geom::Quaternion GetQuaternion() const { + geom::Quaternion carla_quaternion; + // left-handed to right-handed -> negate the rotation by negating all axis components + // switch y-axis from right to left -> negate y-axis + carla_quaternion.x = float(-_ros_quaternion.x()); // -(forward = forward) + carla_quaternion.y = float(_ros_quaternion.y()); // -( right = -left ) + carla_quaternion.z = float(-_ros_quaternion.z()); // -( up = up ) + carla_quaternion.w = float(_ros_quaternion.w()); + return carla_quaternion; + } + +private: + geometry_msgs::msg::Quaternion _ros_quaternion; +}; +} // namespace types +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/RegionOfInterest.h b/LibCarla/source/carla/ros2/types/RegionOfInterest.h deleted file mode 100644 index 64c290fa687..00000000000 --- a/LibCarla/source/carla/ros2/types/RegionOfInterest.h +++ /dev/null @@ -1,286 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// 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. - -/*! - * @file RegionOfInterest.h - * This header file contains the declaration of the described types in the IDL file. - * - * This file was generated by the tool gen. - */ - -#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTEREST_H_ -#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTEREST_H_ - -#include - -#include -#include -#include -#include -#include -#include - -#if defined(_WIN32) -#if defined(EPROSIMA_USER_DLL_EXPORT) -#define eProsima_user_DllExport __declspec( dllexport ) -#else -#define eProsima_user_DllExport -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define eProsima_user_DllExport -#endif // _WIN32 - -#if defined(_WIN32) -#if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(REGIONOFINTEREST_SOURCE) -#define REGIONOFINTEREST_DllAPI __declspec( dllexport ) -#else -#define REGIONOFINTEREST_DllAPI __declspec( dllimport ) -#endif // REGIONOFINTEREST_SOURCE -#else -#define REGIONOFINTEREST_DllAPI -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define REGIONOFINTEREST_DllAPI -#endif // _WIN32 - -namespace eprosima { -namespace fastcdr { -class Cdr; -} // namespace fastcdr -} // namespace eprosima - -namespace sensor_msgs { - namespace msg { - /*! - * @brief This class represents the structure RegionOfInterest defined by the user in the IDL file. - * @ingroup RegionOfInterest - */ - class RegionOfInterest - { - public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport RegionOfInterest(); - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~RegionOfInterest(); - - /*! - * @brief Copy constructor. - * @param x Reference to the object sensor_msgs::msg::RegionOfInterest that will be copied. - */ - eProsima_user_DllExport RegionOfInterest( - const RegionOfInterest& x); - - /*! - * @brief Move constructor. - * @param x Reference to the object sensor_msgs::msg::RegionOfInterest that will be copied. - */ - eProsima_user_DllExport RegionOfInterest( - RegionOfInterest&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object sensor_msgs::msg::RegionOfInterest that will be copied. - */ - eProsima_user_DllExport RegionOfInterest& operator =( - const RegionOfInterest& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object sensor_msgs::msg::RegionOfInterest that will be copied. - */ - eProsima_user_DllExport RegionOfInterest& operator =( - RegionOfInterest&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x sensor_msgs::msg::RegionOfInterest object to compare. - */ - eProsima_user_DllExport bool operator ==( - const RegionOfInterest& x) const; - - /*! - * @brief Comparison operator. - * @param x sensor_msgs::msg::RegionOfInterest object to compare. - */ - eProsima_user_DllExport bool operator !=( - const RegionOfInterest& x) const; - - /*! - * @brief This function sets a value in member x_offset - * @param _x_offset New value for member x_offset - */ - eProsima_user_DllExport void x_offset( - uint32_t _x_offset); - - /*! - * @brief This function returns the value of member x_offset - * @return Value of member x_offset - */ - eProsima_user_DllExport uint32_t x_offset() const; - - /*! - * @brief This function returns a reference to member x_offset - * @return Reference to member x_offset - */ - eProsima_user_DllExport uint32_t& x_offset(); - - /*! - * @brief This function sets a value in member y_offset - * @param _y_offset New value for member y_offset - */ - eProsima_user_DllExport void y_offset( - uint32_t _y_offset); - - /*! - * @brief This function returns the value of member y_offset - * @return Value of member y_offset - */ - eProsima_user_DllExport uint32_t y_offset() const; - - /*! - * @brief This function returns a reference to member y_offset - * @return Reference to member y_offset - */ - eProsima_user_DllExport uint32_t& y_offset(); - - /*! - * @brief This function sets a value in member height - * @param _height New value for member height - */ - eProsima_user_DllExport void height( - uint32_t _height); - - /*! - * @brief This function returns the value of member height - * @return Value of member height - */ - eProsima_user_DllExport uint32_t height() const; - - /*! - * @brief This function returns a reference to member height - * @return Reference to member height - */ - eProsima_user_DllExport uint32_t& height(); - - /*! - * @brief This function sets a value in member width - * @param _width New value for member width - */ - eProsima_user_DllExport void width( - uint32_t _width); - - /*! - * @brief This function returns the value of member width - * @return Value of member width - */ - eProsima_user_DllExport uint32_t width() const; - - /*! - * @brief This function returns a reference to member width - * @return Reference to member width - */ - eProsima_user_DllExport uint32_t& width(); - - /*! - * @brief This function sets a value in member do_rectify - * @param _do_rectify New value for member do_rectify - */ - eProsima_user_DllExport void do_rectify( - bool _do_rectify); - - /*! - * @brief This function returns the value of member do_rectify - * @return Value of member do_rectify - */ - eProsima_user_DllExport bool do_rectify() const; - - /*! - * @brief This function returns a reference to member do_rectify - * @return Reference to member do_rectify - */ - eProsima_user_DllExport bool& do_rectify(); - - - /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ - eProsima_user_DllExport static size_t getMaxCdrSerializedSize( - size_t current_alignment = 0); - - /*! - * @brief This function returns the serialized size of a data depending on the buffer alignment. - * @param data Data which is calculated its serialized size. - * @param current_alignment Buffer alignment. - * @return Serialized size. - */ - eProsima_user_DllExport static size_t getCdrSerializedSize( - const sensor_msgs::msg::RegionOfInterest& data, - size_t current_alignment = 0); - - /*! - * @brief This function serializes an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& cdr) const; - - /*! - * @brief This function deserializes an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr); - - /*! - * @brief This function returns the maximum serialized size of the Key of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ - eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( - size_t current_alignment = 0); - - /*! - * @brief This function tells you if the Key has been defined for this type - */ - eProsima_user_DllExport static bool isKeyDefined(); - - /*! - * @brief This function serializes the key members of an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void serializeKey( - eprosima::fastcdr::Cdr& cdr) const; - - private: - uint32_t m_x_offset; - uint32_t m_y_offset; - uint32_t m_height; - uint32_t m_width; - bool m_do_rectify; - }; - } // namespace msg -} // namespace sensor_msgs - -#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTEREST_H_ diff --git a/LibCarla/source/carla/ros2/types/RegionOfInterestPubSubTypes.h b/LibCarla/source/carla/ros2/types/RegionOfInterestPubSubTypes.h deleted file mode 100644 index 0d9ea9ec08f..00000000000 --- a/LibCarla/source/carla/ros2/types/RegionOfInterestPubSubTypes.h +++ /dev/null @@ -1,143 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// 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. - -/*! - * @file RegionOfInterestPubSubTypes.h - * This header file contains the declaration of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTEREST_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTEREST_PUBSUBTYPES_H_ - -#include -#include - -#include "RegionOfInterest.h" - -#if !defined(GEN_API_VER) || (GEN_API_VER != 1) -#error \ - Generated RegionOfInterest is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. -#endif // GEN_API_VER - -namespace sensor_msgs -{ - namespace msg - { - - #ifndef SWIG - namespace detail { - - template - struct RegionOfInterest_rob - { - friend constexpr typename Tag::type get( - Tag) - { - return M; - } - }; - - struct RegionOfInterest_f - { - typedef bool RegionOfInterest::* type; - friend constexpr type get( - RegionOfInterest_f); - }; - - template struct RegionOfInterest_rob; - - template - inline size_t constexpr RegionOfInterest_offset_of() { - return ((::size_t) &reinterpret_cast((((T*)0)->*get(Tag())))); - } - } - #endif - - /*! - * @brief This class represents the TopicDataType of the type RegionOfInterest defined by the user in the IDL file. - * @ingroup RegionOfInterest - */ - class RegionOfInterestPubSubType : public eprosima::fastdds::dds::TopicDataType - { - public: - - typedef RegionOfInterest type; - - eProsima_user_DllExport RegionOfInterestPubSubType(); - - eProsima_user_DllExport virtual ~RegionOfInterestPubSubType() override; - - eProsima_user_DllExport virtual bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; - - eProsima_user_DllExport virtual bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, - void* data) override; - - eProsima_user_DllExport virtual std::function getSerializedSizeProvider( - void* data) override; - - eProsima_user_DllExport virtual bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport virtual void* createData() override; - - eProsima_user_DllExport virtual void deleteData( - void* data) override; - - #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return true; - } - - #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - - #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return is_plain_impl(); - } - - #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - new (memory) RegionOfInterest(); - return true; - } - - #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - - MD5 m_md5; - unsigned char* m_keyBuffer; - - private: - - static constexpr bool is_plain_impl() - { - return 17ULL == (detail::RegionOfInterest_offset_of() + sizeof(bool)); - - }}; - } -} - -#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTEREST_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/SensorActorDefinition.h b/LibCarla/source/carla/ros2/types/SensorActorDefinition.h new file mode 100644 index 00000000000..ababe643efa --- /dev/null +++ b/LibCarla/source/carla/ros2/types/SensorActorDefinition.h @@ -0,0 +1,42 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/types/ActorNameDefinition.h" +#include "carla/ros2/types/PublisherSensorType.h" +#include "carla/streaming/detail/Types.h" +#include "carla/rpc/CustomV2XBytes.h" +#include "carla/sensor/data/LibITS.h" + +#include + +namespace carla { +namespace ros2 { +namespace types { + +using V2XCustomSendCallback = std::function; + +struct SensorActorDefinition : public ActorNameDefinition { + SensorActorDefinition(ActorNameDefinition const &actor_name_definition, + carla::ros2::types::PublisherSensorType sensor_type_, + carla::streaming::detail::stream_id_type stream_id_) + : ActorNameDefinition(actor_name_definition), sensor_type(sensor_type_), stream_id(stream_id_) {} + + carla::ros2::types::PublisherSensorType sensor_type; + carla::streaming::detail::stream_id_type stream_id; +}; +} // namespace types +} // namespace ros2 +} // namespace carla + +namespace std { + +inline std::string to_string(carla::ros2::types::SensorActorDefinition const &actor_definition) { + return "SensorActor(" + to_string(static_cast(actor_definition)) + + " sensor_type=" + std::to_string(actor_definition.sensor_type) + + " stream_id=" + std::to_string(actor_definition.stream_id) + ")"; +} + +} // namespace std \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/Speed.h b/LibCarla/source/carla/ros2/types/Speed.h new file mode 100644 index 00000000000..0fed649903b --- /dev/null +++ b/LibCarla/source/carla/ros2/types/Speed.h @@ -0,0 +1,65 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/geom/Math.h" +#include "carla/geom/Quaternion.h" +#include "carla/geom/Velocity.h" +#include "std_msgs/msg/Float32.h" + +namespace carla { +namespace ros2 { +namespace types { + +/** + Convert a carla linear Speed to a ROS accel + + Considers the conversion from left-handed system (unreal) to right-handed + system (ROS) + +*/ +class Speed { +public: + /** + * carla_speed: the carla linear Speed + */ + Speed(carla::geom::Velocity const &carla_linear_velocity, carla::geom::Quaternion const &carla_quat) { + _linear_velocity_ros.x = carla_linear_velocity.x; + _linear_velocity_ros.y = -carla_linear_velocity.y; + _linear_velocity_ros.z = carla_linear_velocity.z; + _ros_speed.data(_linear_velocity_ros.Speed(carla_quat)); + } +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + Speed(const FVector &carla_linear_velocity, const FQuat &carla_quat) + : Speed(carla::geom::Velocity(carla_linear_velocity), carla::geom::Quaternion(carla_quat)) {} +#endif // LIBCARLA_INCLUDED_FROM_UE4 + Speed() = default; + ~Speed() = default; + Speed(const Speed &) = default; + Speed &operator=(const Speed &) = default; + Speed(Speed &&) = default; + Speed &operator=(Speed &&) = default; + + /** + * The resulting ROS std_msgs::msg::Float32 + */ + std_msgs::msg::Float32 speed() const { + return _ros_speed; + } + + /** + * The linear velocity as carla::geom::Vector3D but in ROS coordinates + */ + carla::geom::Velocity LinearVelocityROS() const { + return _linear_velocity_ros; + } + +private: + carla::geom::Velocity _linear_velocity_ros; + std_msgs::msg::Float32 _ros_speed; +}; +} // namespace types +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/Timestamp.h b/LibCarla/source/carla/ros2/types/Timestamp.h new file mode 100644 index 00000000000..2dcda7dee09 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/Timestamp.h @@ -0,0 +1,56 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include + +#include "builtin_interfaces/msg/Time.h" + +namespace carla { +namespace ros2 { +namespace types { + +/** + Convert a carla Timestamp to a ROS builtin_interfaces::msg::Time + and holds carla time details +*/ +class Timestamp { +public: + explicit Timestamp(double timestamp = 0.) { + double integral; + const double fractional = std::modf(timestamp, &integral); + _ros_time.sec(static_cast(integral)); + _ros_time.nanosec(static_cast(fractional * 1e9)); + _stamp = double(_ros_time.sec()) + 1e-9 * double(_ros_time.nanosec()); + } + + explicit Timestamp(const builtin_interfaces::msg::Time& time) : _ros_time(time) { + _stamp = double(_ros_time.sec()) + 1e-9 * double(_ros_time.nanosec()); + } + + ~Timestamp() = default; + Timestamp(const Timestamp&) = default; + Timestamp& operator=(const Timestamp&) = default; + Timestamp(Timestamp&&) = default; + Timestamp& operator=(Timestamp&&) = default; + + double Stamp() const { + return _stamp; + } + + /** + * The resulting ROS builtin_interfaces::msg::Time + */ + const builtin_interfaces::msg::Time& time() const { + return _ros_time; + } + +private: + double _stamp{0.}; + builtin_interfaces::msg::Time _ros_time; +}; +} // namespace types +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/TrafficLightActorDefinition.h b/LibCarla/source/carla/ros2/types/TrafficLightActorDefinition.h new file mode 100644 index 00000000000..b2e20dbc309 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/TrafficLightActorDefinition.h @@ -0,0 +1,44 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/types/ActorNameDefinition.h" +#include "carla/sensor/data/ActorDynamicState.h" +#include "carla_msgs/msg/CarlaTrafficLightStatus.h" + +namespace carla { +namespace ros2 { +namespace types { + +inline uint8_t GetTrafficLightState(carla::sensor::data::ActorDynamicState const &actor_dynamic_state) { + switch (actor_dynamic_state.state.traffic_light_data.state) { + case carla::rpc::TrafficLightState::Red: + return carla_msgs::msg::CarlaTrafficLightStatus_Constants::RED; + case carla::rpc::TrafficLightState::Yellow: + return carla_msgs::msg::CarlaTrafficLightStatus_Constants::YELLOW; + case carla::rpc::TrafficLightState::Green: + return carla_msgs::msg::CarlaTrafficLightStatus_Constants::GREEN; + case carla::rpc::TrafficLightState::Off: + return carla_msgs::msg::CarlaTrafficLightStatus_Constants::OFF; + case carla::rpc::TrafficLightState::Unknown: + default: + return carla_msgs::msg::CarlaTrafficLightStatus_Constants::UNKNOWN; + } +} + +struct TrafficLightActorDefinition : public ActorNameDefinition { + TrafficLightActorDefinition(ActorNameDefinition const &actor_definitions) : ActorNameDefinition(actor_definitions) {} +}; +} // namespace types +} // namespace ros2 +} // namespace carla + +namespace std { + +inline std::string to_string(carla::ros2::types::TrafficLightActorDefinition const &actor_definition) { + return "TrafficLightActor(" + to_string(static_cast(actor_definition)) + ")"; +} + +} // namespace std \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/TrafficSignActorDefinition.h b/LibCarla/source/carla/ros2/types/TrafficSignActorDefinition.h new file mode 100644 index 00000000000..63b48014593 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/TrafficSignActorDefinition.h @@ -0,0 +1,28 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/types/ActorNameDefinition.h" + +namespace carla { +namespace ros2 { +namespace types { + +struct TrafficSignActorDefinition : public ActorNameDefinition { + TrafficSignActorDefinition(ActorNameDefinition const &actor_definitions) : ActorNameDefinition(actor_definitions) {} + virtual ~TrafficSignActorDefinition() = default; +}; + +} // namespace types +} // namespace ros2 +} // namespace carla + +namespace std { + +inline std::string to_string(carla::ros2::types::TrafficSignActorDefinition const &actor_definition) { + return "TrafficSignActor(" + to_string(static_cast(actor_definition)) + ")"; +} + +} // namespace std \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/Transform.h b/LibCarla/source/carla/ros2/types/Transform.h index daca6910321..e18fb48c7d0 100644 --- a/LibCarla/source/carla/ros2/types/Transform.h +++ b/LibCarla/source/carla/ros2/types/Transform.h @@ -1,241 +1,143 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// 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. - -/*! - * @file Transform.h - * This header file contains the declaration of the described types in the IDL file. - * - * This file was generated by the tool gen. - */ - -#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORM_H_ -#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORM_H_ - -#include "Vector3.h" -#include "Quaternion.h" - -#include - -#include -#include -#include -#include -#include -#include - -#if defined(_WIN32) -#if defined(EPROSIMA_USER_DLL_EXPORT) -#define eProsima_user_DllExport __declspec( dllexport ) -#else -#define eProsima_user_DllExport -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define eProsima_user_DllExport -#endif // _WIN32 - -#if defined(_WIN32) -#if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(Transform_SOURCE) -#define Transform_DllAPI __declspec( dllexport ) -#else -#define Transform_DllAPI __declspec( dllimport ) -#endif // Transform_SOURCE -#else -#define Transform_DllAPI -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define Transform_DllAPI -#endif // _WIN32 - -namespace eprosima { -namespace fastcdr { -class Cdr; -} // namespace fastcdr -} // namespace eprosima - -namespace geometry_msgs { - namespace msg { - /*! - * @brief This class represents the structure Transform defined by the user in the IDL file. - * @ingroup TRANSFORM - */ - class Transform - { - public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport Transform(); - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~Transform(); - - /*! - * @brief Copy constructor. - * @param x Reference to the object geometry_msgs::msg::Transform that will be copied. - */ - eProsima_user_DllExport Transform( - const Transform& x); - - /*! - * @brief Move constructor. - * @param x Reference to the object geometry_msgs::msg::Transform that will be copied. - */ - eProsima_user_DllExport Transform( - Transform&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object geometry_msgs::msg::Transform that will be copied. - */ - eProsima_user_DllExport Transform& operator =( - const Transform& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object geometry_msgs::msg::Transform that will be copied. - */ - eProsima_user_DllExport Transform& operator =( - Transform&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x geometry_msgs::msg::Transform object to compare. - */ - eProsima_user_DllExport bool operator ==( - const Transform& x) const; - - /*! - * @brief Comparison operator. - * @param x geometry_msgs::msg::Transform object to compare. - */ - eProsima_user_DllExport bool operator !=( - const Transform& x) const; - - /*! - * @brief This function copies the value in member translation - * @param _translation New value to be copied in member translation - */ - eProsima_user_DllExport void translation( - const geometry_msgs::msg::Vector3& _translation); - - /*! - * @brief This function moves the value in member translation - * @param _translation New value to be moved in member translation - */ - eProsima_user_DllExport void translation( - geometry_msgs::msg::Vector3&& _translation); - - /*! - * @brief This function returns a constant reference to member translation - * @return Constant reference to member translation - */ - eProsima_user_DllExport const geometry_msgs::msg::Vector3& translation() const; - - /*! - * @brief This function returns a reference to member translation - * @return Reference to member translation - */ - eProsima_user_DllExport geometry_msgs::msg::Vector3& translation(); - /*! - * @brief This function copies the value in member rotation - * @param _rotation New value to be copied in member rotation - */ - eProsima_user_DllExport void rotation( - const geometry_msgs::msg::Quaternion& _rotation); - - /*! - * @brief This function moves the value in member rotation - * @param _rotation New value to be moved in member rotation - */ - eProsima_user_DllExport void rotation( - geometry_msgs::msg::Quaternion&& _rotation); - - /*! - * @brief This function returns a constant reference to member rotation - * @return Constant reference to member rotation - */ - eProsima_user_DllExport const geometry_msgs::msg::Quaternion& rotation() const; - - /*! - * @brief This function returns a reference to member rotation - * @return Reference to member rotation - */ - eProsima_user_DllExport geometry_msgs::msg::Quaternion& rotation(); - - /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ - eProsima_user_DllExport static size_t getMaxCdrSerializedSize( - size_t current_alignment = 0); - - /*! - * @brief This function returns the serialized size of a data depending on the buffer alignment. - * @param data Data which is calculated its serialized size. - * @param current_alignment Buffer alignment. - * @return Serialized size. - */ - eProsima_user_DllExport static size_t getCdrSerializedSize( - const geometry_msgs::msg::Transform& data, - size_t current_alignment = 0); - - /*! - * @brief This function serializes an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& cdr) const; - - /*! - * @brief This function deserializes an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr); - - /*! - * @brief This function returns the maximum serialized size of the Key of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ - eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( - size_t current_alignment = 0); - - /*! - * @brief This function tells you if the Key has been defined for this type - */ - eProsima_user_DllExport static bool isKeyDefined(); - - /*! - * @brief This function serializes the key members of an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void serializeKey( - eprosima::fastcdr::Cdr& cdr) const; - - private: - geometry_msgs::msg::Vector3 m_translation; - geometry_msgs::msg::Quaternion m_rotation; - }; - } // namespace msg -} // namespace geometry_msgs - -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORM_H_ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/geom/Transform.h" +#include "carla/ros2/types/CoordinateSystemTransform.h" +#include "carla/ros2/types/Quaternion.h" +#include "geometry_msgs/msg/PoseWithCovariance.h" +#include "geometry_msgs/msg/Transform.h" + +namespace carla { +namespace ros2 { +namespace types { + +/** + Convert a carla transform to a ROS transform +*/ +class Transform { +public: + Transform() = default; + + /** + * carla_transform: the carla Transform + */ + explicit Transform(const carla::geom::Transform& carla_transform, const carla::geom::Quaternion& carla_quaternion) + : _carla_transform(carla_transform), _carla_quaternion(carla_quaternion) { + init_ros_transform(); + } + + explicit Transform(const geometry_msgs::msg::Pose& pose) { + _ros_transform.translation().x(pose.position().x()); + _ros_transform.translation().y(pose.position().y()); + _ros_transform.translation().z(pose.position().z()); + _ros_transform.rotation(pose.orientation()); + // switch y-axis from right to left -> negate y-axis + carla::geom::Vector3D ros_location; + ros_location.x = float(pose.position().x()); + ros_location.y = float(pose.position().y()); + ros_location.z = float(pose.position().z()); + _carla_transform.location = CoordinateSystemTransform::TransformLinearAxixVector3D(ros_location); + _carla_quaternion = carla::ros2::types::Quaternion(_ros_transform.rotation()).GetQuaternion(); + } + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + Transform(const FTransform& ue4_transform) + : _carla_transform(ue4_transform), _carla_quaternion(ue4_transform.GetRotation()) { + init_ros_transform(); + } +#endif // LIBCARLA_INCLUDED_FROM_UE4 + + ~Transform() = default; + Transform(const Transform&) = default; + Transform& operator=(const Transform&) = default; + Transform(Transform&&) = default; + Transform& operator=(Transform&&) = default; + + /** + * The resulting ROS geometry_msgs::msg::Transform + * + * Uses ROS naming convention + */ + const geometry_msgs::msg::Transform& transform() const { + return _ros_transform; + } + + /** + * Get the geometry_msgs::msg::Pose that is identical with the geometry_msgs::msg::Transform + * + * Uses ROS naming convention + */ + const geometry_msgs::msg::Pose pose() const { + geometry_msgs::msg::Pose ros_pose; + ros_pose.position().x(_ros_transform.translation().x()); + ros_pose.position().y(_ros_transform.translation().y()); + ros_pose.position().z(_ros_transform.translation().z()); + ros_pose.orientation(_ros_transform.rotation()); + return ros_pose; + } + + /** + * Get the geometry_msgs::msg::PoseWithCovariance that is identical with the geometry_msgs::msg::Transform + * + * Uses ROS naming convention + */ + const geometry_msgs::msg::PoseWithCovariance pose_with_covariance() const { + geometry_msgs::msg::PoseWithCovariance ros_pose_with_covariance; + ros_pose_with_covariance.pose(pose()); + return ros_pose_with_covariance; + } + + /** + * The carla Transform + * + * Uses CARLA naming convention + */ + const carla::geom::Transform& GetTransform() const { + return _carla_transform; + } + + /** + * The carla Location + * + * Uses CARLA naming convention + */ + const carla::geom::Location& GetLocation() const { + return _carla_transform.location; + } + + /** + * The carla Rotator + * + * Uses CARLA naming convention + */ + const carla::geom::Rotation& GetRotator() const { + return _carla_transform.rotation; + } + + /** + * The carla Quaternion + * + * Uses CARLA naming convention + */ + const carla::geom::Quaternion& GetQuaternion() const { + return _carla_quaternion; + } + +private: + void init_ros_transform() { + // switch y-axis from right to left -> negate y-axis + _ros_transform.translation() = CoordinateSystemTransform::TransformLinearAxisMsg(_carla_transform.location); + _ros_transform.rotation(carla::ros2::types::Quaternion(_carla_quaternion).quaternion()); + } + + // keep the carla types for local + carla::geom::Transform _carla_transform; + carla::geom::Quaternion _carla_quaternion; + geometry_msgs::msg::Transform _ros_transform; +}; +} // namespace types +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/TransformPubSubTypes.h b/LibCarla/source/carla/ros2/types/TransformPubSubTypes.h deleted file mode 100644 index a4d04e45461..00000000000 --- a/LibCarla/source/carla/ros2/types/TransformPubSubTypes.h +++ /dev/null @@ -1,143 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// 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. - -/*! - * @file TransformPubSubTypes.h - * This header file contains the declaration of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORM_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORM_PUBSUBTYPES_H_ - -#include -#include - -#include "Transform.h" - -#include "Vector3PubSubTypes.h" -#include "QuaternionPubSubTypes.h" - -#if !defined(GEN_API_VER) || (GEN_API_VER != 1) -#error \ - Generated Transform is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. -#endif // GEN_API_VER - -namespace geometry_msgs -{ - namespace msg - { - - #ifndef SWIG - namespace detail { - - template - struct Transform_rob - { - friend constexpr typename Tag::type get( - Tag) - { - return M; - } - }; - - struct Transform_f - { - typedef geometry_msgs::msg::Quaternion Transform::* type; - friend constexpr type get( - Transform_f); - }; - - template struct Transform_rob; - - template - inline size_t constexpr Transform_offset_of() { - return ((::size_t) &reinterpret_cast((((T*)0)->*get(Tag())))); - } - } - #endif - - /*! - * @brief This class represents the TopicDataType of the type Transform defined by the user in the IDL file. - * @ingroup TRANSFORM - */ - class TransformPubSubType : public eprosima::fastdds::dds::TopicDataType - { - public: - - typedef Transform type; - - eProsima_user_DllExport TransformPubSubType(); - - eProsima_user_DllExport virtual ~TransformPubSubType() override; - - eProsima_user_DllExport virtual bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; - - eProsima_user_DllExport virtual bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, - void* data) override; - - eProsima_user_DllExport virtual std::function getSerializedSizeProvider( - void* data) override; - - eProsima_user_DllExport virtual bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport virtual void* createData() override; - - eProsima_user_DllExport virtual void deleteData( - void* data) override; - - #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return true; - } - - #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - - #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return is_plain_impl(); - } - - #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - new (memory) Transform(); - return true; - } - - #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; - unsigned char* m_keyBuffer; - private: - static constexpr bool is_plain_impl() - { - return 56ULL == (detail::Transform_offset_of() + sizeof(geometry_msgs::msg::Quaternion)); - - }}; - } -} - -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORM_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/Twist.h b/LibCarla/source/carla/ros2/types/Twist.h index 402ed9845fe..54eada3f20f 100644 --- a/LibCarla/source/carla/ros2/types/Twist.h +++ b/LibCarla/source/carla/ros2/types/Twist.h @@ -1,240 +1,62 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// 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. - -/*! - * @file Twist.h - * This header file contains the declaration of the described types in the IDL file. - * - * This file was generated by the tool gen. - */ - -#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWIST_H_ -#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWIST_H_ - -#include "Vector3.h" - -#include - -#include -#include -#include -#include -#include -#include - -#if defined(_WIN32) -#if defined(EPROSIMA_USER_DLL_EXPORT) -#define eProsima_user_DllExport __declspec( dllexport ) -#else -#define eProsima_user_DllExport -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define eProsima_user_DllExport -#endif // _WIN32 - -#if defined(_WIN32) -#if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(Twist_SOURCE) -#define Twist_DllAPI __declspec( dllexport ) -#else -#define Twist_DllAPI __declspec( dllimport ) -#endif // Twist_SOURCE -#else -#define Twist_DllAPI -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define Twist_DllAPI -#endif // _WIN32 - -namespace eprosima { -namespace fastcdr { -class Cdr; -} // namespace fastcdr -} // namespace eprosima - -namespace geometry_msgs { - namespace msg { - /*! - * @brief This class represents the structure Twist defined by the user in the IDL file. - * @ingroup TWIST - */ - class Twist - { - public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport Twist(); - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~Twist(); - - /*! - * @brief Copy constructor. - * @param x Reference to the object geometry_msgs::msg::Twist that will be copied. - */ - eProsima_user_DllExport Twist( - const Twist& x); - - /*! - * @brief Move constructor. - * @param x Reference to the object geometry_msgs::msg::Twist that will be copied. - */ - eProsima_user_DllExport Twist( - Twist&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object geometry_msgs::msg::Twist that will be copied. - */ - eProsima_user_DllExport Twist& operator =( - const Twist& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object geometry_msgs::msg::Twist that will be copied. - */ - eProsima_user_DllExport Twist& operator =( - Twist&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x geometry_msgs::msg::Twist object to compare. - */ - eProsima_user_DllExport bool operator ==( - const Twist& x) const; - - /*! - * @brief Comparison operator. - * @param x geometry_msgs::msg::Twist object to compare. - */ - eProsima_user_DllExport bool operator !=( - const Twist& x) const; - - /*! - * @brief This function copies the value in member linear - * @param _linear New value to be copied in member linear - */ - eProsima_user_DllExport void linear( - const geometry_msgs::msg::Vector3& _linear); - - /*! - * @brief This function moves the value in member linear - * @param _linear New value to be moved in member linear - */ - eProsima_user_DllExport void linear( - geometry_msgs::msg::Vector3&& _linear); - - /*! - * @brief This function returns a constant reference to member linear - * @return Constant reference to member linear - */ - eProsima_user_DllExport const geometry_msgs::msg::Vector3& linear() const; - - /*! - * @brief This function returns a reference to member linear - * @return Reference to member linear - */ - eProsima_user_DllExport geometry_msgs::msg::Vector3& linear(); - /*! - * @brief This function copies the value in member angular - * @param _angular New value to be copied in member angular - */ - eProsima_user_DllExport void angular( - const geometry_msgs::msg::Vector3& _angular); - - /*! - * @brief This function moves the value in member angular - * @param _angular New value to be moved in member angular - */ - eProsima_user_DllExport void angular( - geometry_msgs::msg::Vector3&& _angular); - - /*! - * @brief This function returns a constant reference to member angular - * @return Constant reference to member angular - */ - eProsima_user_DllExport const geometry_msgs::msg::Vector3& angular() const; - - /*! - * @brief This function returns a reference to member angular - * @return Reference to member angular - */ - eProsima_user_DllExport geometry_msgs::msg::Vector3& angular(); - - /*! - * @brief This function returns the maximum serialized size of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ - eProsima_user_DllExport static size_t getMaxCdrSerializedSize( - size_t current_alignment = 0); - - /*! - * @brief This function returns the serialized size of a data depending on the buffer alignment. - * @param data Data which is calculated its serialized size. - * @param current_alignment Buffer alignment. - * @return Serialized size. - */ - eProsima_user_DllExport static size_t getCdrSerializedSize( - const geometry_msgs::msg::Twist& data, - size_t current_alignment = 0); - - /*! - * @brief This function serializes an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& cdr) const; - - /*! - * @brief This function deserializes an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr); - - /*! - * @brief This function returns the maximum serialized size of the Key of an object - * depending on the buffer alignment. - * @param current_alignment Buffer alignment. - * @return Maximum serialized size. - */ - eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize( - size_t current_alignment = 0); - - /*! - * @brief This function tells you if the Key has been defined for this type - */ - eProsima_user_DllExport static bool isKeyDefined(); - - /*! - * @brief This function serializes the key members of an object using CDR serialization. - * @param cdr CDR serialization object. - */ - eProsima_user_DllExport void serializeKey( - eprosima::fastcdr::Cdr& cdr) const; - - private: - geometry_msgs::msg::Vector3 m_linear; - geometry_msgs::msg::Vector3 m_angular; - }; - } // namespace msg -} // namespace geometry_msgs - -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWIST_H_ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/geom/Vector3D.h" +#include "carla/ros2/types/AngularVelocity.h" +#include "carla/ros2/types/Speed.h" +#include "geometry_msgs/msg/TwistWithCovariance.h" + +namespace carla { +namespace ros2 { +namespace types { + +/** + Convert carla velocities to a ROS twist + + Considers the conversion from left-handed system (unreal) to right-handed + system (ROS). +*/ +class Twist { +public: + /** + * carla_Twist: the carla Twist + */ + Twist(Speed const& speed, AngularVelocity const& angular_velocity) { + _ros_twist.linear().x(speed.LinearVelocityROS().x); + _ros_twist.linear().y(speed.LinearVelocityROS().y); + _ros_twist.linear().z(speed.LinearVelocityROS().z); + _ros_twist.angular().x(angular_velocity.AngularVelocityROS().x); + _ros_twist.angular().y(angular_velocity.AngularVelocityROS().y); + _ros_twist.angular().z(angular_velocity.AngularVelocityROS().z); + } + ~Twist() = default; + Twist(const Twist&) = default; + Twist& operator=(const Twist&) = default; + Twist(Twist&&) = default; + Twist& operator=(Twist&&) = default; + + /** + * The resulting ROS geometry_msgs::msg::twist + */ + geometry_msgs::msg::Twist twist() const { + return _ros_twist; + } + + /** + * The resulting ROS geometry_msgs::msg::twist + */ + geometry_msgs::msg::TwistWithCovariance twist_with_covariance() const { + geometry_msgs::msg::TwistWithCovariance _ros_twist_with_covariance; + _ros_twist_with_covariance.twist(_ros_twist); + return _ros_twist_with_covariance; + } + +private: + geometry_msgs::msg::Twist _ros_twist; +}; +} // namespace types +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/TwistPubSubTypes.h b/LibCarla/source/carla/ros2/types/TwistPubSubTypes.h deleted file mode 100644 index b4e959e65be..00000000000 --- a/LibCarla/source/carla/ros2/types/TwistPubSubTypes.h +++ /dev/null @@ -1,142 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// 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. - -/*! - * @file TwistPubSubTypes.h - * This header file contains the declaration of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWIST_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWIST_PUBSUBTYPES_H_ - -#include -#include - -#include "Twist.h" - -#include "Vector3PubSubTypes.h" - -#if !defined(GEN_API_VER) || (GEN_API_VER != 1) -#error \ - Generated Twist is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. -#endif // GEN_API_VER - -namespace geometry_msgs -{ - namespace msg - { - - #ifndef SWIG - namespace detail { - - template - struct Twist_rob - { - friend constexpr typename Tag::type get( - Tag) - { - return M; - } - }; - - struct Twist_f - { - typedef geometry_msgs::msg::Vector3 Twist::* type; - friend constexpr type get( - Twist_f); - }; - - template struct Twist_rob; - - template - inline size_t constexpr Twist_offset_of() { - return ((::size_t) &reinterpret_cast((((T*)0)->*get(Tag())))); - } - } - #endif - - /*! - * @brief This class represents the TopicDataType of the type Twist defined by the user in the IDL file. - * @ingroup TWIST - */ - class TwistPubSubType : public eprosima::fastdds::dds::TopicDataType - { - public: - - typedef Twist type; - - eProsima_user_DllExport TwistPubSubType(); - - eProsima_user_DllExport virtual ~TwistPubSubType() override; - - eProsima_user_DllExport virtual bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; - - eProsima_user_DllExport virtual bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, - void* data) override; - - eProsima_user_DllExport virtual std::function getSerializedSizeProvider( - void* data) override; - - eProsima_user_DllExport virtual bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport virtual void* createData() override; - - eProsima_user_DllExport virtual void deleteData( - void* data) override; - - #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return true; - } - - #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - - #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return is_plain_impl(); - } - - #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - new (memory) Twist(); - return true; - } - - #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; - unsigned char* m_keyBuffer; - private: - static constexpr bool is_plain_impl() - { - return 48ULL == (detail::Twist_offset_of() + sizeof(geometry_msgs::msg::Vector3)); - - }}; - } -} - -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWIST_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/TwistWithCovariancePubSubTypes.h b/LibCarla/source/carla/ros2/types/TwistWithCovariancePubSubTypes.h deleted file mode 100644 index 812d236f643..00000000000 --- a/LibCarla/source/carla/ros2/types/TwistWithCovariancePubSubTypes.h +++ /dev/null @@ -1,142 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// 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. - -/*! - * @file TwistWithCovariancePubSubTypes.h - * This header file contains the declaration of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCE_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCE_PUBSUBTYPES_H_ - -#include -#include - -#include "TwistWithCovariance.h" -#include "TwistPubSubTypes.h" - -#if !defined(GEN_API_VER) || (GEN_API_VER != 1) -#error \ - Generated TwistWithCovariance is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. -#endif // GEN_API_VER - -namespace geometry_msgs -{ - namespace msg - { - typedef std::array geometry_msgs__TwistWithCovariance__double_array_36; - - #ifndef SWIG - namespace detail { - - template - struct TwistWithCovariance_rob - { - friend constexpr typename Tag::type get( - Tag) - { - return M; - } - }; - - struct TwistWithCovariance_f - { - typedef geometry_msgs::msg::geometry_msgs__TwistWithCovariance__double_array_36 TwistWithCovariance::* type; - friend constexpr type get( - TwistWithCovariance_f); - }; - - template struct TwistWithCovariance_rob; - - template - inline size_t constexpr TwistWithCovariance_offset_of() { - return ((::size_t) &reinterpret_cast((((T*)0)->*get(Tag())))); - } - } - #endif - - /*! - * @brief This class represents the TopicDataType of the type TwistWithCovariance defined by the user in the IDL file. - * @ingroup TWISTWITHCOVARIANCE - */ - class TwistWithCovariancePubSubType : public eprosima::fastdds::dds::TopicDataType - { - public: - - typedef TwistWithCovariance type; - - eProsima_user_DllExport TwistWithCovariancePubSubType(); - - eProsima_user_DllExport virtual ~TwistWithCovariancePubSubType() override; - - eProsima_user_DllExport virtual bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override; - - eProsima_user_DllExport virtual bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, - void* data) override; - - eProsima_user_DllExport virtual std::function getSerializedSizeProvider( - void* data) override; - - eProsima_user_DllExport virtual bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport virtual void* createData() override; - - eProsima_user_DllExport virtual void deleteData( - void* data) override; - - #ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return true; - } - - #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - - #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return is_plain_impl(); - } - - #endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - #ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - new (memory) TwistWithCovariance(); - return true; - } - - #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; - unsigned char* m_keyBuffer; - private: - static constexpr bool is_plain_impl() - { - return 336ULL == (detail::TwistWithCovariance_offset_of() + sizeof(geometry_msgs::msg::geometry_msgs__TwistWithCovariance__double_array_36)); - - }}; - } -} - -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCE_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/VehicleAckermannControl.h b/LibCarla/source/carla/ros2/types/VehicleAckermannControl.h new file mode 100644 index 00000000000..0af467957e5 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/VehicleAckermannControl.h @@ -0,0 +1,61 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "ackermann_msgs/msg/AckermannDriveStamped.h" +#include "carla/ros2/types/Timestamp.h" +#include "carla/rpc/VehicleAckermannControl.h" +#include "carla/sensor/data/ActorDynamicState.h" + +namespace carla { +namespace ros2 { +namespace types { + +/** + * VehicleAckermannControl: convert ackermann_msgs::msg::AckermannDriveStamped into FVehicleAckermannControl without the + * need of knowing FVehicleAckermannControl class within LibCarla + */ +class VehicleAckermannControl { +public: + explicit VehicleAckermannControl(const ackermann_msgs::msg::AckermannDriveStamped& vehicle_ackermann_control) + : _vehicle_ackermann_control(vehicle_ackermann_control) {} + ~VehicleAckermannControl() = default; + VehicleAckermannControl(const VehicleAckermannControl&) = default; + VehicleAckermannControl& operator=(const VehicleAckermannControl&) = default; + VehicleAckermannControl(VehicleAckermannControl&&) = default; + VehicleAckermannControl& operator=(VehicleAckermannControl&&) = default; + + ackermann_msgs::msg::AckermannDriveStamped const& carla_vehicle_ackermann_control() const { + return _vehicle_ackermann_control; + } + + VehicleAckermannControl(const carla::rpc::VehicleAckermannControl& vehicle_ackermann_control) { + _vehicle_ackermann_control.header().stamp(Timestamp(vehicle_ackermann_control.timestamp).time()); + _vehicle_ackermann_control.drive().steering_angle(vehicle_ackermann_control.steer); + _vehicle_ackermann_control.drive().steering_angle_velocity(vehicle_ackermann_control.steer_speed); + _vehicle_ackermann_control.drive().speed(vehicle_ackermann_control.speed); + _vehicle_ackermann_control.drive().acceleration(vehicle_ackermann_control.acceleration); + _vehicle_ackermann_control.drive().jerk(vehicle_ackermann_control.jerk); + } + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + + FVehicleAckermannControl GetVehicleAckermannControl() const { + FVehicleAckermannControl vehicle_ackermann_control; + vehicle_ackermann_control.Timestamp = Timestamp(_vehicle_ackermann_control.header().stamp()).Stamp(); + vehicle_ackermann_control.Steer = _vehicle_ackermann_control.drive().steering_angle(); + vehicle_ackermann_control.SteerSpeed = _vehicle_ackermann_control.drive().steering_angle_velocity(); + vehicle_ackermann_control.Speed = _vehicle_ackermann_control.drive().speed(); + vehicle_ackermann_control.Acceleration = _vehicle_ackermann_control.drive().acceleration(); + vehicle_ackermann_control.Jerk = _vehicle_ackermann_control.drive().jerk(); + return vehicle_ackermann_control; + } +#endif // LIBCARLA_INCLUDED_FROM_UE4 +private: + ackermann_msgs::msg::AckermannDriveStamped _vehicle_ackermann_control; +}; +} // namespace types +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/VehicleActorDefinition.h b/LibCarla/source/carla/ros2/types/VehicleActorDefinition.h new file mode 100644 index 00000000000..abcbcdbe4b1 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/VehicleActorDefinition.h @@ -0,0 +1,50 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include + +#include "carla/ros2/types/ActorDefinition.h" +#include "carla/ros2/types/VehicleAckermannControl.h" +#include "carla/ros2/types/VehicleControl.h" +#include "carla/rpc/VehiclePhysicsControl.h" +#include "carla/sensor/data/ActorDynamicState.h" +#include "carla_msgs/msg/CarlaVehicleControlStatus.h" + +namespace carla { +namespace ros2 { +namespace types { + +using VehicleControlCallback = std::function; + +using VehicleAckermannControlCallback = std::function; + +inline uint8_t GetVehicleControlType(carla::sensor::data::ActorDynamicState const &actor_dynamic_state) { + switch (actor_dynamic_state.state.vehicle_data.control_type) { + case carla::rpc::VehicleControlType::AckermannControl: + return carla_msgs::msg::CarlaVehicleControlStatus_Constants::ACKERMANN_CONTROL; + case carla::rpc::VehicleControlType::VehicleControl: + default: + return carla_msgs::msg::CarlaVehicleControlStatus_Constants::VEHICLE_CONTROL; + } +} + +struct VehicleActorDefinition : public ActorDefinition { + VehicleActorDefinition(ActorDefinition const &actor_definition, rpc::VehiclePhysicsControl vehicle_physics_control_in) + : ActorDefinition(actor_definition), vehicle_physics_control(vehicle_physics_control_in) {} + + rpc::VehiclePhysicsControl vehicle_physics_control; +}; +} // namespace types +} // namespace ros2 +} // namespace carla + +namespace std { + +inline std::string to_string(carla::ros2::types::VehicleActorDefinition const &actor_definition) { + return "VehicleActor(" + to_string(static_cast(actor_definition)) + ")"; +} + +} // namespace std diff --git a/LibCarla/source/carla/ros2/types/VehicleControl.h b/LibCarla/source/carla/ros2/types/VehicleControl.h new file mode 100644 index 00000000000..06a555d6514 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/VehicleControl.h @@ -0,0 +1,70 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/types/Timestamp.h" +#include "carla/rpc/VehicleControl.h" +#include "carla/sensor/data/ActorDynamicState.h" +#include "carla_msgs/msg/CarlaVehicleControl.h" + +namespace carla { +namespace ros2 { +namespace types { + +/** + * VehicleControl: convert carla_msgs::msg::CarlaVehicleControl into FVehicleControl without the need of + * knowing FVehicleControl class within LibCarla + */ +class VehicleControl { +public: + explicit VehicleControl(const carla_msgs::msg::CarlaVehicleControl& vehicle_control) + : _vehicle_control(vehicle_control) {} + ~VehicleControl() = default; + VehicleControl(const VehicleControl&) = default; + VehicleControl& operator=(const VehicleControl&) = default; + VehicleControl(VehicleControl&&) = default; + VehicleControl& operator=(VehicleControl&&) = default; + + carla_msgs::msg::CarlaVehicleControl const& carla_vehicle_control() const { + return _vehicle_control; + } + + VehicleControl(const carla::rpc::VehicleControl& vehicle_control, uint8_t control_priority = 0) { + _vehicle_control.header().stamp(Timestamp(vehicle_control.timestamp).time()); + _vehicle_control.throttle(vehicle_control.throttle); + _vehicle_control.steer(vehicle_control.steer); + _vehicle_control.brake(vehicle_control.brake); + _vehicle_control.hand_brake(vehicle_control.hand_brake); + _vehicle_control.reverse(vehicle_control.reverse); + _vehicle_control.gear(vehicle_control.gear); + _vehicle_control.manual_gear_shift(vehicle_control.manual_gear_shift); + _vehicle_control.control_priority(control_priority); + } + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + FVehicleControl GetVehicleControl() const { + FVehicleControl vehicle_control; + vehicle_control.Timestamp = Timestamp(_vehicle_control.header().stamp()).Stamp(); + vehicle_control.Throttle = _vehicle_control.throttle(); + vehicle_control.Steer = _vehicle_control.steer(); + vehicle_control.Brake = _vehicle_control.brake(); + vehicle_control.bHandBrake = _vehicle_control.hand_brake(); + vehicle_control.bReverse = _vehicle_control.reverse(); + vehicle_control.bManualGearShift = _vehicle_control.manual_gear_shift(); + vehicle_control.Gear = _vehicle_control.gear(); + return vehicle_control; + } + + EVehicleInputPriority ControlPriority() const { + return EVehicleInputPriority(_vehicle_control.control_priority()); + } + +#endif // LIBCARLA_INCLUDED_FROM_UE4 +private: + carla_msgs::msg::CarlaVehicleControl _vehicle_control; +}; +} // namespace types +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/WalkerActorDefinition.h b/LibCarla/source/carla/ros2/types/WalkerActorDefinition.h new file mode 100644 index 00000000000..639d63b7069 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/WalkerActorDefinition.h @@ -0,0 +1,32 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include "carla/ros2/types/ActorDefinition.h" +#include "carla/ros2/types/WalkerControl.h" +#include "carla/rpc/WalkerControl.h" + +namespace carla { +namespace ros2 { +namespace types { + +using WalkerControlCallback = std::function; + +struct WalkerActorDefinition : public ActorDefinition { + WalkerActorDefinition(ActorDefinition const &actor_definition) : ActorDefinition(actor_definition) {} + virtual ~WalkerActorDefinition() = default; +}; +} // namespace types +} // namespace ros2 +} // namespace carla + +namespace std { + +inline std::string to_string(carla::ros2::types::WalkerActorDefinition const &actor_definition) { + return "WalkerActor(" + to_string(static_cast(actor_definition)) + ")"; +} + +} // namespace std diff --git a/LibCarla/source/carla/ros2/types/WalkerControl.h b/LibCarla/source/carla/ros2/types/WalkerControl.h new file mode 100644 index 00000000000..2777ebf2bca --- /dev/null +++ b/LibCarla/source/carla/ros2/types/WalkerControl.h @@ -0,0 +1,60 @@ +// Copyright (c) 2022 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/ros2/types/Timestamp.h" +#include "carla/rpc/WalkerControl.h" +#include "carla/sensor/data/ActorDynamicState.h" +#include "carla_msgs/msg/CarlaWalkerControl.h" + +namespace carla { +namespace ros2 { +namespace types { + +/** + * WalkerControl: convert carla_msgs::msg::CarlaWalkerControl into FWalkerControl without the need of + * knowing FWalkerControl class within LibCarla + */ +class WalkerControl { +public: + explicit WalkerControl(const carla_msgs::msg::CarlaWalkerControl& walker_control) : _walker_control(walker_control) {} + ~WalkerControl() = default; + WalkerControl(const WalkerControl&) = default; + WalkerControl& operator=(const WalkerControl&) = default; + WalkerControl(WalkerControl&&) = default; + WalkerControl& operator=(WalkerControl&&) = default; + + carla_msgs::msg::CarlaWalkerControl const& carla_walker_control() const { + return _walker_control; + } + + WalkerControl(const carla::rpc::WalkerControl& walker_control) { + _walker_control.header().stamp(Timestamp(walker_control.timestamp).time()); + _walker_control.direction().x(walker_control.direction.x); + _walker_control.direction().y(walker_control.direction.y); + _walker_control.direction().z(walker_control.direction.z); + _walker_control.speed(walker_control.speed); + _walker_control.jump(walker_control.jump); + } + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + FWalkerControl GetWalkerControl() const { + FWalkerControl walker_control; + walker_control.Timestamp = Timestamp(_walker_control.header().stamp()).Stamp(); + walker_control.Speed = _walker_control.speed(); + walker_control.Direction.X = _walker_control.direction().x(); + walker_control.Direction.Y = -_walker_control.direction().y(); + walker_control.Direction.Z = _walker_control.direction().z(); + walker_control.Jump = _walker_control.jump(); + return walker_control; + } + +#endif // LIBCARLA_INCLUDED_FROM_UE4 +private: + carla_msgs::msg::CarlaWalkerControl _walker_control; +}; +} // namespace types +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/rpc/ActorDefinition.h b/LibCarla/source/carla/rpc/ActorDefinition.h index fe7a65a4bff..6d9debcaa0b 100644 --- a/LibCarla/source/carla/rpc/ActorDefinition.h +++ b/LibCarla/source/carla/rpc/ActorDefinition.h @@ -6,12 +6,18 @@ #pragma once +#include + #include "carla/MsgPack.h" #include "carla/rpc/ActorAttribute.h" #include "carla/rpc/ActorId.h" #include "carla/rpc/String.h" -#include +#ifdef LIBCARLA_INCLUDED_FROM_UE4 +#include +#include "Actor/ActorDefinition.h" +#include +#endif // LIBCARLA_INCLUDED_FROM_UE4 namespace carla { namespace rpc { diff --git a/LibCarla/source/carla/rpc/ActorDescription.h b/LibCarla/source/carla/rpc/ActorDescription.h index 7de63afd512..0415c5100e3 100644 --- a/LibCarla/source/carla/rpc/ActorDescription.h +++ b/LibCarla/source/carla/rpc/ActorDescription.h @@ -6,13 +6,14 @@ #pragma once + +#include + #include "carla/MsgPack.h" #include "carla/rpc/ActorAttribute.h" #include "carla/rpc/ActorId.h" #include "carla/rpc/String.h" -#include - #ifdef LIBCARLA_INCLUDED_FROM_UE4 #include #include "Carla/Actor/ActorDescription.h" diff --git a/LibCarla/source/carla/rpc/CustomV2XBytes.h b/LibCarla/source/carla/rpc/CustomV2XBytes.h new file mode 100644 index 00000000000..123cd0f20ae --- /dev/null +++ b/LibCarla/source/carla/rpc/CustomV2XBytes.h @@ -0,0 +1,26 @@ +// Copyright (c) 2024 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include + +#include "carla/MsgPack.h" + +namespace carla { +namespace rpc { + +class CustomV2XBytes +{ + public: + uint8_t data_size{0u}; + std::array bytes; + MSGPACK_DEFINE_ARRAY(data_size, bytes); +}; + +} // namespace rpc +} // namespace carla diff --git a/LibCarla/source/carla/rpc/RpcServerInterface.h b/LibCarla/source/carla/rpc/RpcServerInterface.h new file mode 100644 index 00000000000..120dd3949b8 --- /dev/null +++ b/LibCarla/source/carla/rpc/RpcServerInterface.h @@ -0,0 +1,107 @@ +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/rpc/Actor.h" +#include "carla/rpc/ActorDefinition.h" +#include "carla/rpc/ActorDescription.h" +#include "carla/rpc/AttachmentType.h" +#include "carla/rpc/EpisodeSettings.h" +#include "carla/rpc/MapInfo.h" +#include "carla/rpc/MapLayer.h" +#include "carla/rpc/Response.h" +#include "carla/rpc/ServerSynchronizationTypes.h" +#include "carla/rpc/Transform.h" +#include "carla/rpc/VehicleTelemetryData.h" +#include "carla/streaming/detail/Dispatcher.h" + +namespace carla { +namespace rpc { + +/// The interface to the CARLA server required from TCP and ROS2 client side. +/// The parts only required from TPC client side are handled by lambdas directly. +class RpcServerInterface { +public: + RpcServerInterface() = default; + virtual ~RpcServerInterface() = default; + + // Server functions to be called also from ROS2 interface. + // Those have to be explicitly callable functions instead of lambdas + virtual std::shared_ptr GetDispatcher() = 0; + + /** + * @brief episode related calls + * @{ + */ + virtual Response call_load_new_episode(const std::string &map_name, const bool reset_settings, MapLayer map_layers) = 0; + virtual Response call_get_episode_settings() = 0; + virtual Response call_set_episode_settings(EpisodeSettings const &settings) = 0; + /** + * @} + */ + + /** + * @brief map related calls + * @{ + */ + virtual Response> call_get_available_maps() = 0; + virtual Response call_get_map_data() = 0; + virtual Response call_get_map_info() = 0; + /** + * @} + */ + + /** + * @brief actor related calls + * @{ + */ + virtual Response > call_get_actor_definitions() = 0; + virtual Response call_spawn_actor(ActorDescription Description, const Transform &Transform) = 0; + virtual Response call_spawn_actor_with_parent(ActorDescription Description, const Transform &Transform, + ActorId ParentId, AttachmentType InAttachmentType, + const std::string &socket_name) = 0; + virtual Response call_destroy_actor(ActorId ActorId) = 0; + virtual Response call_get_telemetry_data(ActorId ActorId) = 0; + + /** + * @} + */ + + /** + * @brief ros actor interaction calls + * @{ + */ + virtual carla::rpc::Response call_enable_actor_for_ros(ActorId actor_id) = 0; + virtual carla::rpc::Response call_disable_actor_for_ros(ActorId actor_id) = 0; + virtual carla::rpc::Response call_is_actor_enabled_for_ros(ActorId actor_id) = 0; + /** + * @} + */ + + /** + * @brief synchronization calls + * @{ + */ + virtual Response call_tick( + synchronization_client_id_type const &client_id = ALL_CLIENTS, + synchronization_participant_id_type const &participant_id = ALL_PARTICIPANTS) = 0; + virtual Response call_register_synchronization_participant( + synchronization_client_id_type const &client_id, + synchronization_participant_id_type const &participant_id_hint = ALL_PARTICIPANTS) = 0; + virtual Response call_deregister_synchronization_participant( + synchronization_client_id_type const &client_id, synchronization_participant_id_type const &participant_id) = 0; + virtual Response call_update_synchronization_window( + synchronization_client_id_type const &client_id, synchronization_participant_id_type const &participant_id, + synchronization_target_game_time const &target_game_time = NO_SYNC_TARGET_GAME_TIME) = 0; + virtual carla::rpc::Response > > call_get_synchronization_window_status() = 0; + /** + * @} + */ +}; + +} // namespace rpc +} // namespace carla diff --git a/LibCarla/source/carla/rpc/Server.h b/LibCarla/source/carla/rpc/Server.h index 38dad188769..279cb168855 100644 --- a/LibCarla/source/carla/rpc/Server.h +++ b/LibCarla/source/carla/rpc/Server.h @@ -65,6 +65,14 @@ namespace rpc { _server.stop(); } + void BindOnClientConnected(::rpc::server::callback_type callback) { + _server.set_on_connection(callback); + } + + void BindOnClientDisconnected(::rpc::server::callback_type callback) { + _server.set_on_disconnection(callback); + } + private: boost::asio::io_context _sync_io_context; diff --git a/LibCarla/source/carla/rpc/ServerSynchronizationTypes.h b/LibCarla/source/carla/rpc/ServerSynchronizationTypes.h new file mode 100644 index 00000000000..e010dfcb8be --- /dev/null +++ b/LibCarla/source/carla/rpc/ServerSynchronizationTypes.h @@ -0,0 +1,33 @@ +// Copyright (c) 2024 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include + +namespace carla { +namespace rpc { + +using synchronization_client_id_type = std::string; +static const carla::rpc::synchronization_client_id_type ALL_CLIENTS{}; + +using synchronization_participant_id_type = uint32_t; +static constexpr carla::rpc::synchronization_participant_id_type ALL_PARTICIPANTS{0}; + +using synchronization_target_game_time = double; +static constexpr synchronization_target_game_time NO_SYNC_TARGET_GAME_TIME{0.}; +static constexpr synchronization_target_game_time BLOCKING_TARGET_GAME_TIME{1e-6}; + +struct synchronization_window_participant_state { + synchronization_client_id_type client_id; + synchronization_participant_id_type participant_id; + synchronization_target_game_time target_game_time; +}; + + + +} // namespace rpc +} // namespace carla diff --git a/LibCarla/source/carla/rpc/Transform.h b/LibCarla/source/carla/rpc/Transform.h index 0af72d66f0f..7b43b99d1ab 100644 --- a/LibCarla/source/carla/rpc/Transform.h +++ b/LibCarla/source/carla/rpc/Transform.h @@ -7,6 +7,7 @@ #pragma once #include "carla/geom/Transform.h" +#include "carla/geom/Quaternion.h" namespace carla { namespace rpc { @@ -15,5 +16,8 @@ namespace rpc { using Transform = geom::Transform; + using Location = geom::Location; + using Quaternion = geom::Quaternion; + } // namespace rpc } // namespace carla diff --git a/LibCarla/source/carla/rpc/VehicleAckermannControl.h b/LibCarla/source/carla/rpc/VehicleAckermannControl.h index 03bf54b9f0f..2d9bdd6327d 100644 --- a/LibCarla/source/carla/rpc/VehicleAckermannControl.h +++ b/LibCarla/source/carla/rpc/VehicleAckermannControl.h @@ -25,18 +25,21 @@ namespace rpc { float in_steer_speed, float in_speed, float in_acceleration, - float in_jerk) + float in_jerk, + float in_timestamp) : steer(in_steer), steer_speed(in_steer_speed), speed(in_speed), acceleration(in_acceleration), - jerk(in_jerk) {} + jerk(in_jerk), + timestamp(in_timestamp) {} float steer = 0.0f; float steer_speed = 0.0f; float speed = 0.0f; float acceleration = 0.0f; float jerk = 0.0f; + float timestamp = 0.f; #ifdef LIBCARLA_INCLUDED_FROM_UE4 @@ -45,7 +48,8 @@ namespace rpc { steer_speed(Control.SteerSpeed), speed(Control.Speed), acceleration(Control.Acceleration), - jerk(Control.Jerk) {} + jerk(Control.Jerk), + timestamp(Control.Timestamp) {} operator FVehicleAckermannControl() const { FVehicleAckermannControl Control; @@ -54,6 +58,7 @@ namespace rpc { Control.Speed = speed; Control.Acceleration = acceleration; Control.Jerk = jerk; + Control.Timestamp = timestamp; return Control; } @@ -65,7 +70,8 @@ namespace rpc { steer_speed != rhs.steer_speed || speed != rhs.speed || acceleration != rhs.acceleration || - jerk != rhs.jerk; + jerk != rhs.jerk || + timestamp != rhs.timestamp; } bool operator==(const VehicleAckermannControl &rhs) const { @@ -77,7 +83,8 @@ namespace rpc { steer_speed, speed, acceleration, - jerk); + jerk, + timestamp); }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/VehicleControl.h b/LibCarla/source/carla/rpc/VehicleControl.h index e413ab9a6d4..d14821e1eb7 100644 --- a/LibCarla/source/carla/rpc/VehicleControl.h +++ b/LibCarla/source/carla/rpc/VehicleControl.h @@ -29,14 +29,16 @@ namespace rpc { bool in_hand_brake, bool in_reverse, bool in_manual_gear_shift, - int32_t in_gear) + int32_t in_gear, + float in_timestamp) : throttle(in_throttle), steer(in_steer), brake(in_brake), hand_brake(in_hand_brake), reverse(in_reverse), manual_gear_shift(in_manual_gear_shift), - gear(in_gear) {} + gear(in_gear), + timestamp(in_timestamp) {} float throttle = 0.0f; float steer = 0.0f; @@ -45,6 +47,7 @@ namespace rpc { bool reverse = false; bool manual_gear_shift = false; int32_t gear = 0; + float timestamp = 0.f; #ifdef LIBCARLA_INCLUDED_FROM_UE4 @@ -55,7 +58,8 @@ namespace rpc { hand_brake(Control.bHandBrake), reverse(Control.bReverse), manual_gear_shift(Control.bManualGearShift), - gear(Control.Gear) {} + gear(Control.Gear), + timestamp(Control.Timestamp) {} operator FVehicleControl() const { FVehicleControl Control; @@ -66,6 +70,7 @@ namespace rpc { Control.bReverse = reverse; Control.bManualGearShift = manual_gear_shift; Control.Gear = gear; + Control.Timestamp = timestamp; return Control; } @@ -79,7 +84,8 @@ namespace rpc { hand_brake != rhs.hand_brake || reverse != rhs.reverse || manual_gear_shift != rhs.manual_gear_shift || - gear != rhs.gear; + gear != rhs.gear || + timestamp != rhs.timestamp; } bool operator==(const VehicleControl &rhs) const { @@ -93,8 +99,10 @@ namespace rpc { hand_brake, reverse, manual_gear_shift, - gear); + gear, + timestamp); }; } // namespace rpc } // namespace carla + diff --git a/LibCarla/source/carla/rpc/VehicleControlType.h b/LibCarla/source/carla/rpc/VehicleControlType.h new file mode 100644 index 00000000000..25862e98770 --- /dev/null +++ b/LibCarla/source/carla/rpc/VehicleControlType.h @@ -0,0 +1,20 @@ +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +namespace carla { +namespace rpc { + + enum class VehicleControlType: uint8_t { + VehicleControl, + AckermannControl + } ; + +} // namespace rpc +} // namespace carla + + diff --git a/LibCarla/source/carla/rpc/WalkerControl.h b/LibCarla/source/carla/rpc/WalkerControl.h index 5343df8e788..65d7d728bb2 100644 --- a/LibCarla/source/carla/rpc/WalkerControl.h +++ b/LibCarla/source/carla/rpc/WalkerControl.h @@ -25,10 +25,12 @@ namespace rpc { WalkerControl( geom::Vector3D in_direction, float in_speed, - bool in_jump) + bool in_jump, + float in_timestamp) : direction(in_direction), speed(in_speed), - jump(in_jump) {} + jump(in_jump), + timestamp(in_timestamp) {} geom::Vector3D direction = {1.0f, 0.0f, 0.0f}; @@ -36,32 +38,37 @@ namespace rpc { bool jump = false; + float timestamp = 0.f; + #ifdef LIBCARLA_INCLUDED_FROM_UE4 WalkerControl(const FWalkerControl &Control) : direction(Control.Direction.X, Control.Direction.Y, Control.Direction.Z), speed(1e-2f * Control.Speed), - jump(Control.Jump) {} + jump(Control.Jump), + timestamp(Control.Timestamp) {} operator FWalkerControl() const { FWalkerControl Control; Control.Direction = {direction.x, direction.y, direction.z}; Control.Speed = 1e2f * speed; Control.Jump = jump; + Control.Timestamp = timestamp; return Control; } #endif // LIBCARLA_INCLUDED_FROM_UE4 bool operator!=(const WalkerControl &rhs) const { - return direction != rhs.direction || speed != rhs.speed || jump != rhs.jump; + return direction != rhs.direction || speed != rhs.speed || jump != rhs.jump || + timestamp != rhs.timestamp; } bool operator==(const WalkerControl &rhs) const { return !(*this != rhs); } - MSGPACK_DEFINE_ARRAY(direction, speed, jump); + MSGPACK_DEFINE_ARRAY(direction, speed, jump, timestamp); }; } // namespace rpc diff --git a/LibCarla/source/carla/rss/RssCheck.cpp b/LibCarla/source/carla/rss/RssCheck.cpp index 713cf9a62e2..970c8d6fdff 100644 --- a/LibCarla/source/carla/rss/RssCheck.cpp +++ b/LibCarla/source/carla/rss/RssCheck.cpp @@ -453,7 +453,7 @@ ::ad::map::match::Object RssCheck::GetMatchObject(carla::SharedPtr - static interpreted_type Deserialize_impl(Data &&data) { + static interpreted_type Deserialize_impl(Data DESERIALIZE_DECL_DATA(data)) { using Serializer = typename Super::template get_by_index::type; - return Serializer::Deserialize(std::forward(data)); + return Serializer::Deserialize(DESERIALIZE_FORWARD_DATA(Data, data)); } + // This function is equivalent to creating a switch statement with a case + // for each element in the map, the compiler should be able to optimize it + // into a jump table. See https://stackoverflow.com/a/46282159/5308925. template - static interpreted_type Deserialize_impl(size_t i, Data &&data, std::index_sequence) { - // This function is equivalent to creating a switch statement with a case - // for each element in the map, the compiler should be able to optimize it - // into a jump table. See https://stackoverflow.com/a/46282159/5308925. + static interpreted_type Deserialize_impl(size_t i, Data DESERIALIZE_DECL_DATA(data), std::index_sequence) { interpreted_type result; std::initializer_list ({ - (i == Is ? (result = Deserialize_impl(std::forward(data))), 0 : 0)... + (i == Is ? (result = Deserialize_impl(DESERIALIZE_FORWARD_DATA(Data, data))), 0 : 0)... }); return result; } template - static interpreted_type Deserialize(size_t index, Data &&data) { + static interpreted_type Deserialize(size_t index, Data DESERIALIZE_DECL_DATA(data)) { return Deserialize_impl( index, - std::forward(data), + DESERIALIZE_FORWARD_DATA(Data, data), std::make_index_sequence()); } }; @@ -85,10 +85,10 @@ namespace sensor { template inline typename CompositeSerializer::interpreted_type - CompositeSerializer::Deserialize(Buffer &&data) { - RawData message{std::move(data)}; + CompositeSerializer::Deserialize(Buffer DESERIALIZE_DECL_DATA(data)) { + RawData message{DESERIALIZE_MOVE_DATA(data)}; size_t index = message.GetSensorTypeId(); - return Deserialize(index, std::move(message)); + return Deserialize(index, DESERIALIZE_MOVE_DATA(message)); } } // namespace sensor diff --git a/LibCarla/source/carla/sensor/Deserializer.cpp b/LibCarla/source/carla/sensor/Deserializer.cpp index 94e65aa566d..8b293e69109 100644 --- a/LibCarla/source/carla/sensor/Deserializer.cpp +++ b/LibCarla/source/carla/sensor/Deserializer.cpp @@ -11,8 +11,8 @@ namespace carla { namespace sensor { - SharedPtr Deserializer::Deserialize(Buffer &&buffer) { - return SensorRegistry::Deserialize(std::move(buffer)); + SharedPtr Deserializer::Deserialize(Buffer DESERIALIZE_DECL_DATA(buffer)) { + return SensorRegistry::Deserialize(DESERIALIZE_MOVE_DATA(buffer)); } } // namespace sensor diff --git a/LibCarla/source/carla/sensor/Deserializer.h b/LibCarla/source/carla/sensor/Deserializer.h index 535ad09813e..8e7e4f9e2c2 100644 --- a/LibCarla/source/carla/sensor/Deserializer.h +++ b/LibCarla/source/carla/sensor/Deserializer.h @@ -9,6 +9,18 @@ #include "carla/Buffer.h" #include "carla/Memory.h" +#if defined(WITH_ROS2) && defined(CARLA_SERVER_BUILD) +// When compiling with ROS2 in server we must not move the data on deserialization +// because the data is used multiple times: by the ROS2 server as well as the TCP server +# define DESERIALIZE_MOVE_DATA(data) data +# define DESERIALIZE_DECL_DATA(data) const &data +# define DESERIALIZE_FORWARD_DATA(type, data) std::forward(data) +#else +# define DESERIALIZE_MOVE_DATA(data) std::move(data) +# define DESERIALIZE_DECL_DATA(data) &&data +# define DESERIALIZE_FORWARD_DATA(type, data) std::forward(data) +#endif + namespace carla { namespace sensor { @@ -22,7 +34,7 @@ namespace sensor { class Deserializer { public: - static SharedPtr Deserialize(Buffer &&buffer); + static SharedPtr Deserialize(Buffer DESERIALIZE_DECL_DATA(buffer)); }; } // namespace sensor diff --git a/LibCarla/source/carla/sensor/RawData.h b/LibCarla/source/carla/sensor/RawData.h index 0e5081c3618..600a926841c 100644 --- a/LibCarla/source/carla/sensor/RawData.h +++ b/LibCarla/source/carla/sensor/RawData.h @@ -8,15 +8,17 @@ #include "carla/Buffer.h" #include "carla/sensor/s11n/SensorHeaderSerializer.h" - -#if defined(WITH_ROS2) -#include "carla/ros2/ROS2.h" -#endif +#include "carla/sensor/Deserializer.h" #include #include namespace carla { + +namespace ros2 { + class ROS2; +} + namespace sensor { /// Wrapper around the raw data generated by a sensor plus some useful @@ -93,13 +95,13 @@ namespace sensor { template friend class CompositeSerializer; - #if defined(WITH_ROS2) - friend class carla::ros2::ROS2; - #endif - - RawData(Buffer &&buffer) : _buffer(std::move(buffer)) {} + RawData(Buffer DESERIALIZE_DECL_DATA(buffer)) : _buffer(DESERIALIZE_MOVE_DATA(buffer)) {} +#if defined(CARLA_SERVER_BUILD) + Buffer const &_buffer; +#else Buffer _buffer; +#endif }; } // namespace sensor diff --git a/LibCarla/source/carla/sensor/data/ActorDynamicState.h b/LibCarla/source/carla/sensor/data/ActorDynamicState.h index f65f07d019f..c2fe27370ae 100644 --- a/LibCarla/source/carla/sensor/data/ActorDynamicState.h +++ b/LibCarla/source/carla/sensor/data/ActorDynamicState.h @@ -7,12 +7,15 @@ #pragma once #include "carla/geom/Transform.h" +#include "carla/geom/Quaternion.h" #include "carla/geom/Vector3D.h" #include "carla/rpc/ActorId.h" #include "carla/rpc/ActorState.h" #include "carla/rpc/VehicleFailureState.h" #include "carla/rpc/TrafficLightState.h" +#include "carla/rpc/VehicleAckermannControl.h" #include "carla/rpc/VehicleControl.h" +#include "carla/rpc/VehicleControlType.h" #include "carla/rpc/WalkerControl.h" #include @@ -36,39 +39,80 @@ namespace detail { hand_brake(control.hand_brake), reverse(control.reverse), manual_gear_shift(control.manual_gear_shift), - gear(control.gear) {} + gear(control.gear), + timestamp(control.timestamp) {} operator rpc::VehicleControl() const { - return {throttle, steer, brake, hand_brake, reverse, manual_gear_shift, gear}; + return {throttle, steer, brake, hand_brake, reverse, manual_gear_shift, gear, timestamp}; } private: - float throttle; - float steer; - float brake; - bool hand_brake; - bool reverse; - bool manual_gear_shift; - int32_t gear; + float throttle = 0.f; + float steer = 0.f; + float brake = 0.f; + bool hand_brake = true; + bool reverse = false; + bool manual_gear_shift = false; + int32_t gear = 0; + float timestamp = 0.f; }; -#pragma pack(pop) + class PackedVehicleAckermannControl { + public: + + PackedVehicleAckermannControl() = default; + + PackedVehicleAckermannControl(const rpc::VehicleAckermannControl &control) + : steer(control.steer), + steer_speed(control.steer_speed), + speed(control.speed), + acceleration(control.acceleration), + jerk(control.jerk), + timestamp(control.timestamp) {} + + operator rpc::VehicleAckermannControl() const { + return {steer, steer_speed, speed, acceleration, jerk, timestamp}; + } + private: + float steer = 0.f; + float steer_speed = 0.f; + float speed = 0.f; + float acceleration = 0.f; + float jerk = 0.f; + float timestamp = 0.f; + }; -#pragma pack(push, 1) struct VehicleData { - VehicleData() = default; + VehicleData()=default; + + rpc::VehicleControlType control_type{ rpc::VehicleControlType::VehicleControl}; + union ControlTypeDependentData { + PackedVehicleControl vehicle_control; + PackedVehicleAckermannControl ackermann_control; + } control_data {PackedVehicleControl()}; + + rpc::VehicleControl GetVehicleControl() const { + if ( rpc::VehicleControlType::VehicleControl == control_type ) { + return control_data.vehicle_control; + } + return rpc::VehicleControl(); + } + + rpc::VehicleAckermannControl GetAckermannControl() const { + if ( rpc::VehicleControlType::AckermannControl == control_type ) { + return control_data.ackermann_control; + } + return rpc::VehicleAckermannControl(); + } - PackedVehicleControl control; float speed_limit; rpc::TrafficLightState traffic_light_state; bool has_traffic_light; rpc::ActorId traffic_light_id; rpc::VehicleFailureState failure_state; }; -#pragma pack(pop) -#pragma pack(push, 1) class PackedWalkerControl { public: @@ -77,10 +121,11 @@ namespace detail { PackedWalkerControl(const rpc::WalkerControl &control) : direction{control.direction.x, control.direction.y, control.direction.z}, speed(control.speed), - jump(control.jump) {} + jump(control.jump), + timestamp(control.timestamp) {} operator rpc::WalkerControl() const { - return {geom::Vector3D{direction[0u], direction[1u], direction[2u]}, speed, jump}; + return {geom::Vector3D{direction[0u], direction[1u], direction[2u]}, speed, jump, timestamp}; } private: @@ -88,12 +133,9 @@ namespace detail { float direction[3u]; float speed; bool jump; + float timestamp; }; -#pragma pack(pop) - -#pragma pack(push, 1) - struct TrafficLightData { TrafficLightData() = default; @@ -106,29 +148,25 @@ namespace detail { bool time_is_frozen; rpc::TrafficLightState state; }; -#pragma pack(pop) - -#pragma pack(push, 1) struct TrafficSignData { TrafficSignData() = default; char sign_id[32u]; }; -#pragma pack(pop) } // namespace detail -#pragma pack(push, 1) - /// Dynamic state of an actor at a certain frame. struct ActorDynamicState { - ActorId id; + ActorId id {0}; rpc::ActorState actor_state; geom::Transform transform; + geom::Quaternion quaternion; + geom::Vector3D velocity; geom::Vector3D angular_velocity; @@ -138,15 +176,15 @@ namespace detail { union TypeDependentState { detail::TrafficLightData traffic_light_data; detail::TrafficSignData traffic_sign_data; - detail::VehicleData vehicle_data; + detail::VehicleData vehicle_data{}; detail::PackedWalkerControl walker_control; } state; }; #pragma pack(pop) - static_assert( - sizeof(ActorDynamicState) == 119u, +static_assert( + sizeof(ActorDynamicState) == 135u, "Invalid ActorDynamicState size! " "If you modified this class please update the size here, else you may " "comment this assert, but your platform may have compatibility issues " diff --git a/LibCarla/source/carla/sensor/data/Array.h b/LibCarla/source/carla/sensor/data/Array.h index 968214a05e1..240c552acc8 100644 --- a/LibCarla/source/carla/sensor/data/Array.h +++ b/LibCarla/source/carla/sensor/data/Array.h @@ -6,13 +6,7 @@ #pragma once -#include "carla/Debug.h" -#include "carla/Exception.h" -#include "carla/sensor/SensorData.h" - -#include -#include -#include +#include "carla/sensor/data/ArrayConst.h" namespace carla { namespace sensor { @@ -20,23 +14,23 @@ namespace data { /// Base class for all the sensor data consisting of an array of items. template - class Array : public SensorData { + class Array : public ArrayConst { + private: + using ArrayConst::_data; + using ArrayConst::_offset; + public: - using value_type = T; + using value_type = typename ArrayConst::value_type; using iterator = value_type *; - using const_iterator = typename std::add_const::type *; + using const_iterator = typename ArrayConst::const_iterator; using reverse_iterator = std::reverse_iterator; - using const_reverse_iterator = std::reverse_iterator; - using size_type = size_t; + using const_reverse_iterator = typename ArrayConst::const_reverse_iterator; + using size_type = typename ArrayConst::size_type; using pointer = value_type *; - using const_pointer = typename std::add_const::type *; + using const_pointer = typename ArrayConst::const_pointer; using reference = value_type &; - using const_reference = typename std::add_const::type &; - - iterator begin() { - return reinterpret_cast(_data.begin() + _offset); - } + using const_reference = typename ArrayConst::const_reference; const_iterator cbegin() const { return reinterpret_cast(_data.begin() + _offset); @@ -46,10 +40,6 @@ namespace data { return cbegin(); } - iterator end() { - return reinterpret_cast(_data.end()); - } - const_iterator cend() const { return reinterpret_cast(_data.end()); } @@ -57,11 +47,6 @@ namespace data { const_iterator end() const { return cend(); } - - reverse_iterator rbegin() { - return reverse_iterator(begin()); - } - const_reverse_iterator crbegin() const { return const_reverse_iterator(cbegin()); } @@ -70,10 +55,6 @@ namespace data { return crbegin(); } - reverse_iterator rend() { - return reverse_iterator(end()); - } - const_reverse_iterator crend() const { return const_reverse_iterator(cend()); } @@ -82,13 +63,24 @@ namespace data { return crend(); } - bool empty() const { - return begin() == end(); + iterator begin() { + return reinterpret_cast(const_cast(&_data)->begin() + _offset); } - size_type size() const { - DEBUG_ASSERT(std::distance(begin(), end()) >= 0); - return static_cast(std::distance(begin(), end())); + iterator end() { + return reinterpret_cast(const_cast(&_data)->end()); + } + + reverse_iterator rbegin() { + return reverse_iterator(begin()); + } + + reverse_iterator rend() { + return reverse_iterator(end()); + } + + bool empty() const { + return begin() == end(); } value_type *data() { @@ -99,52 +91,41 @@ namespace data { return begin(); } - reference operator[](size_type pos) { - return data()[pos]; - } - const_reference operator[](size_type pos) const { return data()[pos]; } - reference at(size_type pos) { + const_reference at(size_type pos) const { if (!(pos < size())) { throw_exception(std::out_of_range("Array index out of range")); } return operator[](pos); } - const_reference at(size_type pos) const { + reference operator[](size_type pos) { + return data()[pos]; + } + + reference at(size_type pos) { if (!(pos < size())) { throw_exception(std::out_of_range("Array index out of range")); } return operator[](pos); } + using ArrayConst::size; + protected: template - explicit Array(RawData &&data, FuncT get_offset) - : SensorData(data), - _data(std::move(data)), - _offset(get_offset(_data)) { - DEBUG_ASSERT(_data.size() >= _offset); - DEBUG_ASSERT((_data.size() - _offset) % sizeof(T) == 0u); - DEBUG_ASSERT(begin() <= end()); - } - - explicit Array(size_t offset, RawData &&data) - : Array(std::move(data), [offset](const RawData &) { return offset; }) {} - - const RawData &GetRawData() const { - return _data; - } - - private: + explicit Array(RawData DESERIALIZE_DECL_DATA(data), FuncT get_offset) + : ArrayConst(DESERIALIZE_MOVE_DATA(data), get_offset) {} + + explicit Array(size_t offset, RawData DESERIALIZE_DECL_DATA(data)) + : ArrayConst(offset, DESERIALIZE_MOVE_DATA(data)) {} - RawData _data; + using ArrayConst::GetRawData; - const size_t _offset; }; } // namespace data diff --git a/LibCarla/source/carla/sensor/data/ArrayConst.h b/LibCarla/source/carla/sensor/data/ArrayConst.h new file mode 100644 index 00000000000..8381f7a7370 --- /dev/null +++ b/LibCarla/source/carla/sensor/data/ArrayConst.h @@ -0,0 +1,128 @@ +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "carla/Debug.h" +#include "carla/Exception.h" +#include "carla/sensor/SensorData.h" +#include "carla/sensor/Deserializer.h" + +#include +#include +#include + +namespace carla { +namespace sensor { +namespace data { + + template + class Array; + + /// Base class for all the sensor data consisting of an array of items. + /// This class provides const access to the data, which is the normal use-case + /// If non-const access is required, use the derived Array class which casts away the constiness + template + class ArrayConst : public SensorData { + public: + + using value_type = T; + using const_iterator = typename std::add_const::type *; + using const_reverse_iterator = std::reverse_iterator; + using size_type = size_t; + using const_pointer = typename std::add_const::type *; + using const_reference = typename std::add_const::type &; + + const_iterator cbegin() const { + return reinterpret_cast(_data.begin() + _offset); + } + + const_iterator begin() const { + return cbegin(); + } + + const_iterator cend() const { + return reinterpret_cast(_data.end()); + } + + const_iterator end() const { + return cend(); + } + const_reverse_iterator crbegin() const { + return const_reverse_iterator(cbegin()); + } + + const_reverse_iterator rbegin() const { + return crbegin(); + } + + const_reverse_iterator crend() const { + return const_reverse_iterator(cend()); + } + + const_reverse_iterator rend() const { + return crend(); + } + + bool empty() const { + return begin() == end(); + } + + size_type size() const { + DEBUG_ASSERT(std::distance(begin(), end()) >= 0); + return static_cast(std::distance(begin(), end())); + } + + const value_type *data() const { + return begin(); + } + + const_reference operator[](size_type pos) const { + return data()[pos]; + } + + const_reference at(size_type pos) const { + if (!(pos < size())) { + throw_exception(std::out_of_range("Array index out of range")); + } + return operator[](pos); + } + + protected: + + template + explicit ArrayConst(RawData DESERIALIZE_DECL_DATA(data), FuncT get_offset) + : SensorData(data), + _data(DESERIALIZE_MOVE_DATA(data)), + _offset(get_offset(_data)) { + DEBUG_ASSERT(_data.size() >= _offset); + DEBUG_ASSERT((_data.size() - _offset) % sizeof(T) == 0u); + DEBUG_ASSERT(begin() <= end()); + } + + explicit ArrayConst(size_t offset, RawData DESERIALIZE_DECL_DATA(data)) + : ArrayConst(DESERIALIZE_MOVE_DATA(data), [offset](RawData const &) { return offset; }) {} + + const RawData &GetRawData() const { + return _data; + } + + private: + template + friend class Array; + +#if defined(CARLA_SERVER_BUILD) + const RawData &_data; +#else + RawData _data; +#endif + + const size_t _offset; + }; + +} // namespace data +} // namespace sensor +} // namespace carla diff --git a/LibCarla/source/carla/sensor/data/DVSEventArray.h b/LibCarla/source/carla/sensor/data/DVSEventArray.h index 603aa53b0df..055f2b0d960 100644 --- a/LibCarla/source/carla/sensor/data/DVSEventArray.h +++ b/LibCarla/source/carla/sensor/data/DVSEventArray.h @@ -25,8 +25,8 @@ namespace data { friend Serializer; - explicit DVSEventArray(RawData &&data) - : Super(Serializer::header_offset, std::move(data)) { + explicit DVSEventArray(RawData DESERIALIZE_DECL_DATA(data)) + : Super(Serializer::header_offset, DESERIALIZE_MOVE_DATA(data)) { } private: diff --git a/LibCarla/source/carla/sensor/data/GnssMeasurement.h b/LibCarla/source/carla/sensor/data/GnssMeasurement.h index fa812d2e0b3..98182bf2a11 100644 --- a/LibCarla/source/carla/sensor/data/GnssMeasurement.h +++ b/LibCarla/source/carla/sensor/data/GnssMeasurement.h @@ -25,12 +25,10 @@ namespace data { friend Serializer; - explicit GnssMeasurement(const RawData &&data) + explicit GnssMeasurement(const RawData DESERIALIZE_DECL_DATA(data)) : Super(data){ - - geom::GeoLocation gnss_data = Serializer::DeserializeRawData(data); + geom::GeoLocation gnss_data = Serializer::DeserializeRawData(DESERIALIZE_MOVE_DATA(data)); _geo_location = gnss_data; - } public: diff --git a/LibCarla/source/carla/sensor/data/ImageTmpl.h b/LibCarla/source/carla/sensor/data/ImageTmpl.h index 70206fe7bd7..fc6a41fd554 100644 --- a/LibCarla/source/carla/sensor/data/ImageTmpl.h +++ b/LibCarla/source/carla/sensor/data/ImageTmpl.h @@ -14,10 +14,6 @@ #include "carla/sensor/s11n/GBufferFloatSerializer.h" #include "carla/sensor/s11n/NormalsImageSerializer.h" -#if defined(WITH_ROS2) -#include "carla/ros2/ROS2.h" -#endif - namespace carla { namespace sensor { namespace data { @@ -26,10 +22,6 @@ namespace data { template class ImageTmpl : public Array { using Super = Array; - #if defined(WITH_ROS2) - friend class carla::ros2::ROS2; - #endif - protected: using Serializer = s11n::ImageSerializer; @@ -42,8 +34,8 @@ namespace data { friend s11n::GBufferFloatSerializer; friend SerializerNormals; - explicit ImageTmpl(RawData &&data) - : Super(Serializer::header_offset, std::move(data)) { + explicit ImageTmpl(RawData DESERIALIZE_DECL_DATA(data)) + : Super(Serializer::header_offset, DESERIALIZE_MOVE_DATA(data)) { DEBUG_ASSERT(GetWidth() * GetHeight() == Super::size()); } diff --git a/LibCarla/source/carla/sensor/data/LibITS.h b/LibCarla/source/carla/sensor/data/LibITS.h index b3f419b6a3a..bc565ad28a1 100644 --- a/LibCarla/source/carla/sensor/data/LibITS.h +++ b/LibCarla/source/carla/sensor/data/LibITS.h @@ -1,8 +1,11 @@ #pragma once #include -#include +#include #include +#include "carla/rpc/CustomV2XBytes.h" + + class ITSContainer { @@ -531,7 +534,7 @@ class ITSContainer /* ProtectedCommunicationZonesRSU */ typedef struct ProtectedCommunicationZonesRSU { long ProtectedCommunicationZoneCount; - std::vector list; + std::array data; /* (SIZE(1..16)) */ } ProtectedCommunicationZonesRSU_t; /* VehicleRole Dependencies */ @@ -626,7 +629,7 @@ class ITSContainer /* PathHistory */ typedef struct PathHistory { long NumberOfPathPoint; - std::vector data; + std::array data; /* (SIZE(0..40)) */ } PathHistory_t; }; @@ -752,8 +755,6 @@ class CAMContainer GenerationDeltaTime_t generationDeltaTime; CamParameters_t camParameters; } CoopAwareness_t; - - }; /* CoopAwareness */ @@ -763,9 +764,8 @@ class CAMContainer CAMContainer::CoopAwareness_t cam; } CAM_t; - typedef struct CustomV2XM { ITSContainer::ItsPduHeader_t header; - char message[100]; + carla::rpc::CustomV2XBytes data; } CustomV2XM_t; diff --git a/LibCarla/source/carla/sensor/data/LidarData.h b/LibCarla/source/carla/sensor/data/LidarData.h index 749925edf9c..34e9be7c693 100644 --- a/LibCarla/source/carla/sensor/data/LidarData.h +++ b/LibCarla/source/carla/sensor/data/LidarData.h @@ -14,10 +14,6 @@ namespace carla { -namespace ros2 { - class ROS2; -} - namespace sensor { namespace s11n { @@ -112,7 +108,6 @@ namespace data { friend class s11n::LidarSerializer; friend class s11n::LidarHeaderView; - friend class carla::ros2::ROS2; }; } // namespace s11n diff --git a/LibCarla/source/carla/sensor/data/LidarMeasurement.h b/LibCarla/source/carla/sensor/data/LidarMeasurement.h index 48ad3290220..67235e84ab7 100644 --- a/LibCarla/source/carla/sensor/data/LidarMeasurement.h +++ b/LibCarla/source/carla/sensor/data/LidarMeasurement.h @@ -26,8 +26,8 @@ namespace data { friend Serializer; - explicit LidarMeasurement(RawData &&data) - : Super(std::move(data), [](const RawData &d) { + explicit LidarMeasurement(RawData DESERIALIZE_DECL_DATA(data)) + : Super(DESERIALIZE_MOVE_DATA(data), [](const RawData &d) { return Serializer::GetHeaderOffset(d); }) {} diff --git a/LibCarla/source/carla/sensor/data/RadarData.h b/LibCarla/source/carla/sensor/data/RadarData.h index c464530aeb6..63d263193f1 100644 --- a/LibCarla/source/carla/sensor/data/RadarData.h +++ b/LibCarla/source/carla/sensor/data/RadarData.h @@ -12,10 +12,6 @@ namespace carla { -namespace ros2 { - class ROS2; -} - namespace sensor { namespace s11n { @@ -74,7 +70,6 @@ namespace data { std::vector _detections; friend class s11n::RadarSerializer; - friend class carla::ros2::ROS2; }; } // namespace s11n diff --git a/LibCarla/source/carla/sensor/data/RadarMeasurement.h b/LibCarla/source/carla/sensor/data/RadarMeasurement.h index b746323c0bc..2f17996ca19 100644 --- a/LibCarla/source/carla/sensor/data/RadarMeasurement.h +++ b/LibCarla/source/carla/sensor/data/RadarMeasurement.h @@ -25,8 +25,9 @@ namespace data { friend Serializer; - explicit RadarMeasurement(RawData &&data) - : Super(0u, std::move(data)) {} + explicit RadarMeasurement(RawData DESERIALIZE_DECL_DATA(data)) + : Super(0u, DESERIALIZE_MOVE_DATA(data)) {} + public: diff --git a/LibCarla/source/carla/sensor/data/RawEpisodeState.h b/LibCarla/source/carla/sensor/data/RawEpisodeState.h index 6a8e6d87336..a778ff1b130 100644 --- a/LibCarla/source/carla/sensor/data/RawEpisodeState.h +++ b/LibCarla/source/carla/sensor/data/RawEpisodeState.h @@ -8,7 +8,7 @@ #include "carla/Debug.h" #include "carla/sensor/data/ActorDynamicState.h" -#include "carla/sensor/data/Array.h" +#include "carla/sensor/data/ArrayConst.h" #include "carla/sensor/s11n/EpisodeStateSerializer.h" namespace carla { @@ -16,16 +16,16 @@ namespace sensor { namespace data { /// State of the episode at a given frame. - class RawEpisodeState : public Array { - using Super = Array; + class RawEpisodeState : public ArrayConst { + using Super = ArrayConst; protected: using Serializer = s11n::EpisodeStateSerializer; friend Serializer; - explicit RawEpisodeState(RawData &&data) - : Super(Serializer::header_offset, std::move(data)) {} + explicit RawEpisodeState(RawData DESERIALIZE_DECL_DATA(data)) + : Super(Serializer::header_offset, DESERIALIZE_MOVE_DATA(data)) {} private: diff --git a/LibCarla/source/carla/sensor/data/SemanticLidarData.h b/LibCarla/source/carla/sensor/data/SemanticLidarData.h index a7b4f8ea12d..00948ca23c8 100644 --- a/LibCarla/source/carla/sensor/data/SemanticLidarData.h +++ b/LibCarla/source/carla/sensor/data/SemanticLidarData.h @@ -14,10 +14,6 @@ namespace carla { -namespace ros2 { - class ROS2; -} - namespace sensor { namespace s11n { @@ -127,7 +123,7 @@ namespace data { } virtual void WriteChannelCount(std::vector points_per_channel) { - for (auto idxChannel = 0u; idxChannel < GetChannelCount(); ++idxChannel) + for (auto idxChannel = 0u; idxChannel < GetChannelCount() && idxChannel < points_per_channel.size(); ++idxChannel) _header[Index::SIZE + idxChannel] = points_per_channel[idxChannel]; } @@ -144,7 +140,6 @@ namespace data { friend class s11n::SemanticLidarHeaderView; friend class s11n::SemanticLidarSerializer; - friend class carla::ros2::ROS2; }; diff --git a/LibCarla/source/carla/sensor/data/SemanticLidarMeasurement.h b/LibCarla/source/carla/sensor/data/SemanticLidarMeasurement.h index 790e1a088c9..f3812f9aa3f 100644 --- a/LibCarla/source/carla/sensor/data/SemanticLidarMeasurement.h +++ b/LibCarla/source/carla/sensor/data/SemanticLidarMeasurement.h @@ -26,8 +26,8 @@ namespace data { friend Serializer; - explicit SemanticLidarMeasurement(RawData &&data) - : Super(std::move(data), [](const RawData &d) { + explicit SemanticLidarMeasurement(RawData DESERIALIZE_DECL_DATA(data)) + : Super(DESERIALIZE_MOVE_DATA(data), [](const RawData &d) { return Serializer::GetHeaderOffset(d); }) {} diff --git a/LibCarla/source/carla/sensor/data/SerializerVectorAllocator.h b/LibCarla/source/carla/sensor/data/SerializerVectorAllocator.h new file mode 100644 index 00000000000..f926633b22a --- /dev/null +++ b/LibCarla/source/carla/sensor/data/SerializerVectorAllocator.h @@ -0,0 +1,124 @@ +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include + +#include "carla/Exception.h" +#include "carla/BufferView.h" + +namespace carla { +namespace sensor { +namespace data { + + /** + * @brief Allocator to allow copyless conversion from an Image Serializer into a std::vector that uses the existing buffer data + * The prevents from calling memcpy() or similar. + */ + template + class SerializerVectorAllocator: public std::allocator + { + public: + using std::allocator::allocator; + using pointer = typename std::allocator_traits>::pointer; + using size_type = typename std::allocator_traits>::size_type; + using const_pointer = typename std::allocator_traits>::const_pointer; + + pointer allocate(size_type n, const void *hint=0) + { + (void)hint; + if (_is_allocated) { + carla::throw_exception(std::range_error("SerializerVectorAllocator:: memory already allocated")); + } + size_type const overall_size = sizeof(T)*n; + if ( overall_size == _buffer->size() - _header_offset ) { + return reinterpret_cast(const_cast(_buffer->data() + _header_offset)); + } + else { + carla::throw_exception(std::range_error("SerializerVectorAllocator::allocate buffer size is " + std::to_string(_buffer->size()) + + " header offset is " + std::to_string(_header_offset) + + " but requested overall size is " + std::to_string(overall_size))); + } + + return nullptr; + } + + void deallocate(pointer p, size_type n) + { + (void)p; + size_type const overall_size = sizeof(T)*n; + if ( overall_size == _buffer->size() - _header_offset ) { + _is_allocated = false; + } + else { + carla::throw_exception(std::range_error("SerializerVectorAllocator::deallocate buffer size is " + std::to_string(_buffer->size()) + + " header offset is " + std::to_string(_header_offset) + + " but requested overall size is " + std::to_string(overall_size))); + } + } + + /** + * nothing is initialized because it would overwrite the buffer data + */ + template void construct(U*, Args&&...) { + } + + SerializerVectorAllocator(const carla::SharedBufferView buffer, size_type header_offset) : + std::allocator(), + _buffer(buffer), + _header_offset(header_offset) { + } + ~SerializerVectorAllocator() = default; + + private: + carla::SharedBufferView _buffer; + size_type _header_offset {0u}; + bool _is_allocated{false}; + }; + + /** + * @brief calculates the number of elements of the buffer view by reducing the buffer size by the provided header_offset and division by sizeof(T) + */ + template + std::size_t number_of_elements(const carla::SharedBufferView buffer, size_t header_offset) { + return (buffer->size() - header_offset) / sizeof(T); + } + + /** + * @brief create a vector with custom allocator providing the buffer memory + * + * This provides std::vector access to the buffer data while leaving out the header_offset. + * The vector size is deduced from number_of_elements(). + * This is a copyless operation, but the vector data cannot be assigned/moved to a std::vector with standard allocator without copy. + */ + template + std::vector> buffer_data_accessed_by_vector(const carla::SharedBufferView buffer_view, size_t header_offset) { + auto number_of_elements = carla::sensor::data::number_of_elements(buffer_view, header_offset); + std::vector> vector_data( + number_of_elements, + std::move(carla::sensor::data::SerializerVectorAllocator(buffer_view, header_offset))); + return vector_data; + } + + + /** + * @brief create a vector with default allocator and copy the data from buffer memory + * + * This provides std::vector copy of the buffer data while leaving out the carla::sensor::s11n::ImageSerializer::header_offset. + * The vector size is deduced from number_of_elements(). + * This is a operation performing copy operation, but the vector data cannot be assigned/moved to a std::vector with standard allocator without copy. + */ + template + std::vector buffer_data_copy_to_std_vector(const carla::SharedBufferView buffer_view, size_t header_offset) { + auto buffer_data = buffer_data_accessed_by_vector(buffer_view, header_offset); + std::vector vector_data(buffer_data.begin(), buffer_data.end()); + return vector_data; + } + +} // namespace data +} // namespace sensor +} // namespace carla diff --git a/LibCarla/source/carla/sensor/data/V2XData.h b/LibCarla/source/carla/sensor/data/V2XData.h index 4747b5ef88a..590763f9be2 100644 --- a/LibCarla/source/carla/sensor/data/V2XData.h +++ b/LibCarla/source/carla/sensor/data/V2XData.h @@ -41,10 +41,6 @@ namespace carla { public: - explicit CAMDataS() = default; - - CAMDataS &operator=(CAMDataS &&) = default; - // Returns the number of current received messages. size_t GetMessageCount() const { @@ -58,7 +54,7 @@ namespace carla } // Adds a new detection. - void WriteMessage(CAMData message) + void WriteMessage(CAMData const &message) { MessageList.push_back(message); } @@ -73,10 +69,6 @@ namespace carla { public: - explicit CustomV2XDataS() = default; - - CustomV2XDataS &operator=(CustomV2XDataS &&) = default; - // Returns the number of current received messages. size_t GetMessageCount() const { @@ -90,7 +82,7 @@ namespace carla } // Adds a new detection. - void WriteMessage(CustomV2XData message) + void WriteMessage(CustomV2XData const &message) { MessageList.push_back(message); } diff --git a/LibCarla/source/carla/sensor/data/V2XEvent.h b/LibCarla/source/carla/sensor/data/V2XEvent.h index f146bffb112..5d7153dd8f6 100644 --- a/LibCarla/source/carla/sensor/data/V2XEvent.h +++ b/LibCarla/source/carla/sensor/data/V2XEvent.h @@ -27,8 +27,8 @@ namespace carla friend Serializer; - explicit CAMEvent(RawData &&data) - : Super(0u, std::move(data)) {} + explicit CAMEvent(RawData DESERIALIZE_DECL_DATA(data)) + : Super(0u, DESERIALIZE_MOVE_DATA(data)) {} public: Super::size_type GetMessageCount() const @@ -46,8 +46,8 @@ namespace carla friend Serializer; - explicit CustomV2XEvent(RawData &&data) - : Super(0u, std::move(data)) {} + explicit CustomV2XEvent(RawData DESERIALIZE_DECL_DATA(data)) + : Super(0u, DESERIALIZE_MOVE_DATA(data)) {} public: Super::size_type GetMessageCount() const diff --git a/LibCarla/source/carla/sensor/s11n/CollisionEventSerializer.cpp b/LibCarla/source/carla/sensor/s11n/CollisionEventSerializer.cpp index 588cca8e564..968e9334ce6 100644 --- a/LibCarla/source/carla/sensor/s11n/CollisionEventSerializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/CollisionEventSerializer.cpp @@ -11,8 +11,8 @@ namespace carla { namespace sensor { namespace s11n { - SharedPtr CollisionEventSerializer::Deserialize(RawData &&data) { - return SharedPtr(new data::CollisionEvent(std::move(data))); + SharedPtr CollisionEventSerializer::Deserialize(RawData DESERIALIZE_DECL_DATA(data)) { + return SharedPtr(new data::CollisionEvent(DESERIALIZE_MOVE_DATA(data))); } } // namespace s11n diff --git a/LibCarla/source/carla/sensor/s11n/CollisionEventSerializer.h b/LibCarla/source/carla/sensor/s11n/CollisionEventSerializer.h index 11d5c032567..54ccc1e6869 100644 --- a/LibCarla/source/carla/sensor/s11n/CollisionEventSerializer.h +++ b/LibCarla/source/carla/sensor/s11n/CollisionEventSerializer.h @@ -50,7 +50,7 @@ namespace s11n { return MsgPack::Pack(Data{self_actor, other_actor, normal_impulse}); } - static SharedPtr Deserialize(RawData &&data); + static SharedPtr Deserialize(RawData DESERIALIZE_DECL_DATA(data)); }; } // namespace s11n diff --git a/LibCarla/source/carla/sensor/s11n/DVSEventArraySerializer.cpp b/LibCarla/source/carla/sensor/s11n/DVSEventArraySerializer.cpp index 7f1533ad7f3..1aa0ef71e22 100644 --- a/LibCarla/source/carla/sensor/s11n/DVSEventArraySerializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/DVSEventArraySerializer.cpp @@ -12,11 +12,8 @@ namespace carla { namespace sensor { namespace s11n { - SharedPtr DVSEventArraySerializer::Deserialize(RawData &&data) { - - auto events_array = SharedPtr(new data::DVSEventArray{std::move(data)}); - - return events_array; + SharedPtr DVSEventArraySerializer::Deserialize(RawData DESERIALIZE_DECL_DATA(data)) { + return SharedPtr(new data::DVSEventArray{DESERIALIZE_MOVE_DATA(data)}); } } // namespace s11n diff --git a/LibCarla/source/carla/sensor/s11n/DVSEventArraySerializer.h b/LibCarla/source/carla/sensor/s11n/DVSEventArraySerializer.h index bc7ed0f735d..1f66c1be1a5 100644 --- a/LibCarla/source/carla/sensor/s11n/DVSEventArraySerializer.h +++ b/LibCarla/source/carla/sensor/s11n/DVSEventArraySerializer.h @@ -42,7 +42,7 @@ namespace s11n { template static Buffer Serialize(const Sensor &sensor, const DVSEventArray &events, Buffer &&output); - static SharedPtr Deserialize(RawData &&data); + static SharedPtr Deserialize(RawData DESERIALIZE_DECL_DATA(data)); }; template diff --git a/LibCarla/source/carla/sensor/s11n/EpisodeStateSerializer.cpp b/LibCarla/source/carla/sensor/s11n/EpisodeStateSerializer.cpp index 564b009f194..7517c150247 100644 --- a/LibCarla/source/carla/sensor/s11n/EpisodeStateSerializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/EpisodeStateSerializer.cpp @@ -12,8 +12,8 @@ namespace carla { namespace sensor { namespace s11n { - SharedPtr EpisodeStateSerializer::Deserialize(RawData &&data) { - return SharedPtr(new data::RawEpisodeState{std::move(data)}); + SharedPtr EpisodeStateSerializer::Deserialize(RawData DESERIALIZE_DECL_DATA(data)) { + return SharedPtr(new data::RawEpisodeState{DESERIALIZE_MOVE_DATA(data)}); } } // namespace s11n diff --git a/LibCarla/source/carla/sensor/s11n/EpisodeStateSerializer.h b/LibCarla/source/carla/sensor/s11n/EpisodeStateSerializer.h index 16709991f31..d6d2e04abaf 100644 --- a/LibCarla/source/carla/sensor/s11n/EpisodeStateSerializer.h +++ b/LibCarla/source/carla/sensor/s11n/EpisodeStateSerializer.h @@ -54,7 +54,8 @@ namespace s11n { return std::move(buffer); } - static SharedPtr Deserialize(RawData &&data); + static SharedPtr Deserialize(RawData DESERIALIZE_DECL_DATA(data)); + }; } // namespace s11n diff --git a/LibCarla/source/carla/sensor/s11n/GBufferFloatSerializer.cpp b/LibCarla/source/carla/sensor/s11n/GBufferFloatSerializer.cpp index 680ac8a1341..2a28c3081fe 100644 --- a/LibCarla/source/carla/sensor/s11n/GBufferFloatSerializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/GBufferFloatSerializer.cpp @@ -12,9 +12,8 @@ namespace carla { namespace sensor { namespace s11n { - SharedPtr GBufferFloatSerializer::Deserialize(RawData &&data) { - auto image = SharedPtr(new data::FloatImage{std::move(data)}); - return image; + SharedPtr GBufferFloatSerializer::Deserialize(RawData DESERIALIZE_DECL_DATA(data)) { + return SharedPtr(new data::FloatImage{DESERIALIZE_MOVE_DATA(data)}); } } // namespace s11n diff --git a/LibCarla/source/carla/sensor/s11n/GBufferFloatSerializer.h b/LibCarla/source/carla/sensor/s11n/GBufferFloatSerializer.h index f80b270a995..12c91dc2553 100644 --- a/LibCarla/source/carla/sensor/s11n/GBufferFloatSerializer.h +++ b/LibCarla/source/carla/sensor/s11n/GBufferFloatSerializer.h @@ -41,7 +41,8 @@ namespace s11n { static Buffer Serialize(const Sensor &sensor, Buffer &&bitmap, uint32_t ImageWidth, uint32_t ImageHeight, float FovAngle); - static SharedPtr Deserialize(RawData &&data); + static SharedPtr Deserialize(RawData DESERIALIZE_DECL_DATA(data)); + }; template diff --git a/LibCarla/source/carla/sensor/s11n/GBufferUint8Serializer.cpp b/LibCarla/source/carla/sensor/s11n/GBufferUint8Serializer.cpp index 5289fbab714..ac2367a6eae 100644 --- a/LibCarla/source/carla/sensor/s11n/GBufferUint8Serializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/GBufferUint8Serializer.cpp @@ -12,9 +12,8 @@ namespace carla { namespace sensor { namespace s11n { - SharedPtr GBufferUint8Serializer::Deserialize(RawData &&data) { - auto image = SharedPtr(new data::Image{std::move(data)}); - return image; + SharedPtr GBufferUint8Serializer::Deserialize(RawData DESERIALIZE_DECL_DATA(data)) { + return SharedPtr(new data::Image{DESERIALIZE_MOVE_DATA(data)}); } } // namespace s11n diff --git a/LibCarla/source/carla/sensor/s11n/GBufferUint8Serializer.h b/LibCarla/source/carla/sensor/s11n/GBufferUint8Serializer.h index 552267f4eab..cdc197ff57f 100644 --- a/LibCarla/source/carla/sensor/s11n/GBufferUint8Serializer.h +++ b/LibCarla/source/carla/sensor/s11n/GBufferUint8Serializer.h @@ -41,7 +41,8 @@ namespace s11n { static Buffer Serialize(const Sensor &sensor, Buffer &&bitmap, uint32_t ImageWidth, uint32_t ImageHeight, float FovAngle); - static SharedPtr Deserialize(RawData &&data); + static SharedPtr Deserialize(RawData DESERIALIZE_DECL_DATA(data)); + }; template diff --git a/LibCarla/source/carla/sensor/s11n/GnssSerializer.cpp b/LibCarla/source/carla/sensor/s11n/GnssSerializer.cpp index 9ef5887d3ec..06e019bda33 100644 --- a/LibCarla/source/carla/sensor/s11n/GnssSerializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/GnssSerializer.cpp @@ -12,8 +12,8 @@ namespace carla { namespace sensor { namespace s11n { - SharedPtr GnssSerializer::Deserialize(RawData &&data) { - return SharedPtr(new data::GnssMeasurement(std::move(data))); + SharedPtr GnssSerializer::Deserialize(RawData DESERIALIZE_DECL_DATA(data)) { + return SharedPtr(new data::GnssMeasurement(DESERIALIZE_MOVE_DATA(data))); } } // namespace s11n diff --git a/LibCarla/source/carla/sensor/s11n/GnssSerializer.h b/LibCarla/source/carla/sensor/s11n/GnssSerializer.h index 97331a8d3a5..ab51a2d227d 100644 --- a/LibCarla/source/carla/sensor/s11n/GnssSerializer.h +++ b/LibCarla/source/carla/sensor/s11n/GnssSerializer.h @@ -36,7 +36,8 @@ namespace s11n { return MsgPack::Pack(geo_location); } - static SharedPtr Deserialize(RawData &&data); + static SharedPtr Deserialize(RawData DESERIALIZE_DECL_DATA(data)); + }; } // namespace s11n diff --git a/LibCarla/source/carla/sensor/s11n/IMUSerializer.cpp b/LibCarla/source/carla/sensor/s11n/IMUSerializer.cpp index 309ff9d8cf9..9310f73d3ea 100644 --- a/LibCarla/source/carla/sensor/s11n/IMUSerializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/IMUSerializer.cpp @@ -11,8 +11,8 @@ namespace carla { namespace sensor { namespace s11n { - SharedPtr IMUSerializer::Deserialize(RawData &&data) { - return SharedPtr(new data::IMUMeasurement(std::move(data))); + SharedPtr IMUSerializer::Deserialize(RawData DESERIALIZE_DECL_DATA(data)) { + return SharedPtr(new data::IMUMeasurement(DESERIALIZE_MOVE_DATA(data))); } } // namespace s11n diff --git a/LibCarla/source/carla/sensor/s11n/IMUSerializer.h b/LibCarla/source/carla/sensor/s11n/IMUSerializer.h index 6b5cf0ed46d..5b305506f1b 100644 --- a/LibCarla/source/carla/sensor/s11n/IMUSerializer.h +++ b/LibCarla/source/carla/sensor/s11n/IMUSerializer.h @@ -43,7 +43,8 @@ namespace s11n { return MsgPack::UnPack(message.begin(), message.size()); } - static SharedPtr Deserialize(RawData &&data); + static SharedPtr Deserialize(RawData DESERIALIZE_DECL_DATA(data)); + }; template diff --git a/LibCarla/source/carla/sensor/s11n/ImageSerializer.cpp b/LibCarla/source/carla/sensor/s11n/ImageSerializer.cpp index cfcc3540d1e..cbf3e9292cd 100644 --- a/LibCarla/source/carla/sensor/s11n/ImageSerializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/ImageSerializer.cpp @@ -12,8 +12,8 @@ namespace carla { namespace sensor { namespace s11n { - SharedPtr ImageSerializer::Deserialize(RawData &&data) { - auto image = SharedPtr(new data::Image{std::move(data)}); + SharedPtr ImageSerializer::Deserialize(RawData DESERIALIZE_DECL_DATA(data)) { + auto image = SharedPtr(new data::Image{DESERIALIZE_MOVE_DATA(data)}); // Set alpha of each pixel in the buffer to max to make it 100% opaque for (auto &pixel : *image) { pixel.a = 255u; @@ -21,6 +21,8 @@ namespace s11n { return image; } + + } // namespace s11n } // namespace sensor } // namespace carla diff --git a/LibCarla/source/carla/sensor/s11n/ImageSerializer.h b/LibCarla/source/carla/sensor/s11n/ImageSerializer.h index 57a3ed7a3c4..10361fc909a 100644 --- a/LibCarla/source/carla/sensor/s11n/ImageSerializer.h +++ b/LibCarla/source/carla/sensor/s11n/ImageSerializer.h @@ -40,7 +40,8 @@ namespace s11n { template static Buffer Serialize(const Sensor &sensor, Buffer &&bitmap); - static SharedPtr Deserialize(RawData &&data); + static SharedPtr Deserialize(RawData DESERIALIZE_DECL_DATA(data)); + }; template diff --git a/LibCarla/source/carla/sensor/s11n/LidarSerializer.cpp b/LibCarla/source/carla/sensor/s11n/LidarSerializer.cpp index 28858a16e13..1bc948d1473 100644 --- a/LibCarla/source/carla/sensor/s11n/LidarSerializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/LidarSerializer.cpp @@ -12,9 +12,8 @@ namespace carla { namespace sensor { namespace s11n { - SharedPtr LidarSerializer::Deserialize(RawData &&data) { - return SharedPtr( - new data::LidarMeasurement{std::move(data)}); + SharedPtr LidarSerializer::Deserialize(RawData DESERIALIZE_DECL_DATA(data)) { + return SharedPtr(new data::LidarMeasurement{DESERIALIZE_MOVE_DATA(data)}); } } // namespace s11n diff --git a/LibCarla/source/carla/sensor/s11n/LidarSerializer.h b/LibCarla/source/carla/sensor/s11n/LidarSerializer.h index 29862ef5dda..19ed5bba3d2 100644 --- a/LibCarla/source/carla/sensor/s11n/LidarSerializer.h +++ b/LibCarla/source/carla/sensor/s11n/LidarSerializer.h @@ -12,6 +12,12 @@ #include "carla/sensor/data/LidarData.h" namespace carla { + +namespace ros2 { + template + class UePublisherBasePointCloud; +} // namespace ros2 + namespace sensor { class SensorData; @@ -40,8 +46,21 @@ namespace s11n { return _begin[Index::SIZE + channel]; } + size_t GetHeaderOffset() const { + return sizeof(uint32_t) * (GetChannelCount() + data::LidarData::Index::SIZE); + } + + size_t GetDataSize() const { + size_t data_size=0u; + for (size_t i=0; i; explicit LidarHeaderView(const uint32_t *begin) : _begin(begin) { DEBUG_ASSERT(_begin != nullptr); @@ -63,8 +82,7 @@ namespace s11n { } static size_t GetHeaderOffset(const RawData &data) { - auto View = DeserializeHeader(data); - return sizeof(uint32_t) * (View.GetChannelCount() + data::LidarData::Index::SIZE); + return DeserializeHeader(data).GetHeaderOffset(); } template @@ -73,7 +91,8 @@ namespace s11n { const data::LidarData &data, Buffer &&output); - static SharedPtr Deserialize(RawData &&data); + static SharedPtr Deserialize(RawData DESERIALIZE_DECL_DATA(data)); + }; // =========================================================================== diff --git a/LibCarla/source/carla/sensor/s11n/NoopSerializer.cpp b/LibCarla/source/carla/sensor/s11n/NoopSerializer.cpp index ee4648c345c..be242eafde2 100644 --- a/LibCarla/source/carla/sensor/s11n/NoopSerializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/NoopSerializer.cpp @@ -12,7 +12,8 @@ namespace carla { namespace sensor { namespace s11n { - SharedPtr NoopSerializer::Deserialize(RawData &&) { + SharedPtr NoopSerializer::Deserialize(RawData DESERIALIZE_DECL_DATA(data)) { + (void)data; throw_exception(std::runtime_error("NoopSerializer: Invalid data received.")); } diff --git a/LibCarla/source/carla/sensor/s11n/NoopSerializer.h b/LibCarla/source/carla/sensor/s11n/NoopSerializer.h index cf77cefd12d..7e930883472 100644 --- a/LibCarla/source/carla/sensor/s11n/NoopSerializer.h +++ b/LibCarla/source/carla/sensor/s11n/NoopSerializer.h @@ -24,7 +24,8 @@ namespace s11n { class NoopSerializer { public: - [[ noreturn ]] static SharedPtr Deserialize(RawData &&data); + [[ noreturn ]] static SharedPtr Deserialize(RawData DESERIALIZE_DECL_DATA(data)); + }; } // namespace s11n diff --git a/LibCarla/source/carla/sensor/s11n/NormalsImageSerializer.cpp b/LibCarla/source/carla/sensor/s11n/NormalsImageSerializer.cpp index 895006e2289..d1940ed035c 100644 --- a/LibCarla/source/carla/sensor/s11n/NormalsImageSerializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/NormalsImageSerializer.cpp @@ -11,8 +11,8 @@ namespace carla { namespace sensor { namespace s11n { - SharedPtr NormalsImageSerializer::Deserialize(RawData &&data) { - auto image = SharedPtr(new data::NormalsImage{std::move(data)}); + SharedPtr NormalsImageSerializer::Deserialize(RawData DESERIALIZE_DECL_DATA(data)) { + auto image = SharedPtr(new data::NormalsImage{DESERIALIZE_MOVE_DATA(data)}); return image; } diff --git a/LibCarla/source/carla/sensor/s11n/NormalsImageSerializer.h b/LibCarla/source/carla/sensor/s11n/NormalsImageSerializer.h index 4944b665d72..c3259de8ed9 100644 --- a/LibCarla/source/carla/sensor/s11n/NormalsImageSerializer.h +++ b/LibCarla/source/carla/sensor/s11n/NormalsImageSerializer.h @@ -38,7 +38,8 @@ namespace carla { template static Buffer Serialize(const Sensor &sensor, Buffer &&bitmap); - static SharedPtr Deserialize(RawData &&data); + static SharedPtr Deserialize(RawData DESERIALIZE_DECL_DATA(data)); + }; template diff --git a/LibCarla/source/carla/sensor/s11n/ObstacleDetectionEventSerializer.cpp b/LibCarla/source/carla/sensor/s11n/ObstacleDetectionEventSerializer.cpp index f2473f2c0c7..ccba6bade74 100644 --- a/LibCarla/source/carla/sensor/s11n/ObstacleDetectionEventSerializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/ObstacleDetectionEventSerializer.cpp @@ -11,8 +11,8 @@ namespace carla { namespace sensor { namespace s11n { - SharedPtr ObstacleDetectionEventSerializer::Deserialize(RawData &&data) { - return SharedPtr(new data::ObstacleDetectionEvent(std::move(data))); + SharedPtr ObstacleDetectionEventSerializer::Deserialize(RawData DESERIALIZE_DECL_DATA(data)) { + return SharedPtr(new data::ObstacleDetectionEvent(DESERIALIZE_MOVE_DATA(data))); } } // namespace s11n diff --git a/LibCarla/source/carla/sensor/s11n/ObstacleDetectionEventSerializer.h b/LibCarla/source/carla/sensor/s11n/ObstacleDetectionEventSerializer.h index 7ba7246bfcf..59c1e8ff284 100644 --- a/LibCarla/source/carla/sensor/s11n/ObstacleDetectionEventSerializer.h +++ b/LibCarla/source/carla/sensor/s11n/ObstacleDetectionEventSerializer.h @@ -49,7 +49,8 @@ namespace s11n { return MsgPack::Pack(Data{self_actor, other_actor, distance}); } - static SharedPtr Deserialize(RawData &&data); + static SharedPtr Deserialize(RawData DESERIALIZE_DECL_DATA(data)); + }; } // namespace s11n diff --git a/LibCarla/source/carla/sensor/s11n/OpticalFlowImageSerializer.cpp b/LibCarla/source/carla/sensor/s11n/OpticalFlowImageSerializer.cpp index 543f94dd209..3758ee6c11f 100644 --- a/LibCarla/source/carla/sensor/s11n/OpticalFlowImageSerializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/OpticalFlowImageSerializer.cpp @@ -11,8 +11,8 @@ namespace carla { namespace sensor { namespace s11n { - SharedPtr OpticalFlowImageSerializer::Deserialize(RawData &&data) { - auto image = SharedPtr(new data::OpticalFlowImage{std::move(data)}); + SharedPtr OpticalFlowImageSerializer::Deserialize(RawData DESERIALIZE_DECL_DATA(data)) { + auto image = SharedPtr(new data::OpticalFlowImage{DESERIALIZE_MOVE_DATA(data)}); return image; } diff --git a/LibCarla/source/carla/sensor/s11n/OpticalFlowImageSerializer.h b/LibCarla/source/carla/sensor/s11n/OpticalFlowImageSerializer.h index 655360e48f2..1f2901b6bf8 100644 --- a/LibCarla/source/carla/sensor/s11n/OpticalFlowImageSerializer.h +++ b/LibCarla/source/carla/sensor/s11n/OpticalFlowImageSerializer.h @@ -38,7 +38,8 @@ namespace carla { template static Buffer Serialize(const Sensor &sensor, Buffer &&bitmap); - static SharedPtr Deserialize(RawData &&data); + static SharedPtr Deserialize(RawData DESERIALIZE_DECL_DATA(data)); + }; template diff --git a/LibCarla/source/carla/sensor/s11n/RadarSerializer.cpp b/LibCarla/source/carla/sensor/s11n/RadarSerializer.cpp index 76b439e99e0..5b4db3848d1 100644 --- a/LibCarla/source/carla/sensor/s11n/RadarSerializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/RadarSerializer.cpp @@ -12,9 +12,9 @@ namespace carla { namespace sensor { namespace s11n { - SharedPtr RadarSerializer::Deserialize(RawData &&data) { + SharedPtr RadarSerializer::Deserialize(RawData DESERIALIZE_DECL_DATA(data)) { return SharedPtr( - new data::RadarMeasurement{std::move(data)}); + new data::RadarMeasurement{DESERIALIZE_MOVE_DATA(data)}); } } // namespace s11n diff --git a/LibCarla/source/carla/sensor/s11n/RadarSerializer.h b/LibCarla/source/carla/sensor/s11n/RadarSerializer.h index 3cd458a03ad..029684a6eba 100644 --- a/LibCarla/source/carla/sensor/s11n/RadarSerializer.h +++ b/LibCarla/source/carla/sensor/s11n/RadarSerializer.h @@ -34,7 +34,8 @@ namespace s11n { const data::RadarData &measurement, Buffer &&output); - static SharedPtr Deserialize(RawData &&data); + static SharedPtr Deserialize(RawData DESERIALIZE_DECL_DATA(data)); + }; template diff --git a/LibCarla/source/carla/sensor/s11n/SemanticLidarSerializer.cpp b/LibCarla/source/carla/sensor/s11n/SemanticLidarSerializer.cpp index 5dc1c673d5b..ae0f7a9180b 100644 --- a/LibCarla/source/carla/sensor/s11n/SemanticLidarSerializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/SemanticLidarSerializer.cpp @@ -11,9 +11,9 @@ namespace carla { namespace sensor { namespace s11n { - SharedPtr SemanticLidarSerializer::Deserialize(RawData &&data) { + SharedPtr SemanticLidarSerializer::Deserialize(RawData DESERIALIZE_DECL_DATA(data)) { return SharedPtr( - new data::SemanticLidarMeasurement{std::move(data)}); + new data::SemanticLidarMeasurement{DESERIALIZE_MOVE_DATA(data)}); } } // namespace s11n diff --git a/LibCarla/source/carla/sensor/s11n/SemanticLidarSerializer.h b/LibCarla/source/carla/sensor/s11n/SemanticLidarSerializer.h index b3d8b39ce59..6da058504ae 100644 --- a/LibCarla/source/carla/sensor/s11n/SemanticLidarSerializer.h +++ b/LibCarla/source/carla/sensor/s11n/SemanticLidarSerializer.h @@ -12,6 +12,12 @@ #include "carla/sensor/data/SemanticLidarData.h" namespace carla { + +namespace ros2 { + template + class UePublisherBasePointCloud; +} // namespace ros2 + namespace sensor { class SensorData; @@ -41,8 +47,21 @@ namespace s11n { return _begin[Index::SIZE + channel]; } + size_t GetHeaderOffset() const { + return sizeof(uint32_t) * (GetChannelCount() + Index::SIZE); + } + + size_t GetDataSize() const { + size_t data_size=0u; + for (size_t i=0; i; explicit SemanticLidarHeaderView(const uint32_t *begin) : _begin(begin) { DEBUG_ASSERT(_begin != nullptr); @@ -65,7 +84,7 @@ namespace s11n { static size_t GetHeaderOffset(const RawData &data) { auto View = DeserializeHeader(data); - return sizeof(uint32_t) * (View.GetChannelCount() + data::SemanticLidarData::Index::SIZE); + return View.GetHeaderOffset(); } template @@ -74,7 +93,8 @@ namespace s11n { const data::SemanticLidarData &measurement, Buffer &&output); - static SharedPtr Deserialize(RawData &&data); + static SharedPtr Deserialize(RawData DESERIALIZE_DECL_DATA(data)); + }; // =========================================================================== diff --git a/LibCarla/source/carla/sensor/s11n/SensorHeaderSerializer.cpp b/LibCarla/source/carla/sensor/s11n/SensorHeaderSerializer.cpp index 0c64e6f2aaf..e1c1123efc5 100644 --- a/LibCarla/source/carla/sensor/s11n/SensorHeaderSerializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/SensorHeaderSerializer.cpp @@ -13,7 +13,7 @@ namespace sensor { namespace s11n { static_assert( - SensorHeaderSerializer::header_offset == 3u * 8u + 6u * 4u, + SensorHeaderSerializer::header_offset == 3u * 8u + /* 2x Transform */ 2u * 6u * 4u + /* quaternion */ 4u * 4u, "Header size missmatch"); static Buffer PopBufferFromPool() { @@ -25,12 +25,17 @@ namespace s11n { const uint64_t index, const uint64_t frame, double timestamp, - const rpc::Transform transform) { + const rpc::Transform &transform, + const rpc::Transform &sensor_relative_transform, + const rpc::Quaternion &sensor_relative_transform_quaternion + ) { Header h; h.sensor_type = index; h.frame = frame; h.timestamp = timestamp; h.sensor_transform = transform; + h.sensor_relative_transform = sensor_relative_transform; + h.sensor_relative_transform_quaternion = sensor_relative_transform_quaternion; auto buffer = PopBufferFromPool(); buffer.copy_from(reinterpret_cast(&h), sizeof(h)); return buffer; diff --git a/LibCarla/source/carla/sensor/s11n/SensorHeaderSerializer.h b/LibCarla/source/carla/sensor/s11n/SensorHeaderSerializer.h index ebcb0090d40..3d40217feea 100644 --- a/LibCarla/source/carla/sensor/s11n/SensorHeaderSerializer.h +++ b/LibCarla/source/carla/sensor/s11n/SensorHeaderSerializer.h @@ -23,6 +23,8 @@ namespace s11n { uint64_t frame; double timestamp; rpc::Transform sensor_transform; + rpc::Transform sensor_relative_transform; + rpc::Quaternion sensor_relative_transform_quaternion; }; #pragma pack(pop) @@ -32,7 +34,10 @@ namespace s11n { uint64_t index, uint64_t frame, double timestamp, - rpc::Transform transform); + const rpc::Transform &transform, + const rpc::Transform &sensor_relative_transform, + const rpc::Quaternion &sensor_relative_transform_quaternion + ); static const Header &Deserialize(const Buffer &message) { return *reinterpret_cast(message.data()); diff --git a/LibCarla/source/carla/sensor/s11n/V2XSerializer.cpp b/LibCarla/source/carla/sensor/s11n/V2XSerializer.cpp index 7853afac71b..23c0d3d2392 100644 --- a/LibCarla/source/carla/sensor/s11n/V2XSerializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/V2XSerializer.cpp @@ -15,14 +15,14 @@ namespace carla namespace s11n { - SharedPtr CAMDataSerializer::Deserialize(RawData &&data) + SharedPtr CAMDataSerializer::Deserialize(RawData DESERIALIZE_DECL_DATA(data)) { - return SharedPtr(new data::CAMEvent(std::move(data))); + return SharedPtr(new data::CAMEvent(DESERIALIZE_MOVE_DATA(data))); } - SharedPtr CustomV2XDataSerializer::Deserialize(RawData &&data) + SharedPtr CustomV2XDataSerializer::Deserialize(RawData DESERIALIZE_DECL_DATA(data)) { - return SharedPtr(new data::CustomV2XEvent(std::move(data))); + return SharedPtr(new data::CustomV2XEvent(DESERIALIZE_MOVE_DATA(data))); } } // namespace s11n diff --git a/LibCarla/source/carla/sensor/s11n/V2XSerializer.h b/LibCarla/source/carla/sensor/s11n/V2XSerializer.h index 4c38aed47b4..c8e90251513 100644 --- a/LibCarla/source/carla/sensor/s11n/V2XSerializer.h +++ b/LibCarla/source/carla/sensor/s11n/V2XSerializer.h @@ -38,7 +38,7 @@ namespace carla const data::CAMDataS &data, Buffer &&output); - static SharedPtr Deserialize(RawData &&data); + static SharedPtr Deserialize(RawData DESERIALIZE_DECL_DATA(data)); }; template @@ -61,7 +61,7 @@ namespace carla const data::CustomV2XDataS &data, Buffer &&output); - static SharedPtr Deserialize(RawData &&data); + static SharedPtr Deserialize(RawData DESERIALIZE_DECL_DATA(data)); }; template diff --git a/LibCarla/source/carla/streaming/Server.h b/LibCarla/source/carla/streaming/Server.h index 95fbc489457..f3a17cd221e 100644 --- a/LibCarla/source/carla/streaming/Server.h +++ b/LibCarla/source/carla/streaming/Server.h @@ -75,16 +75,24 @@ namespace streaming { return _server.GetToken(sensor_id); } - void EnableForROS(stream_id sensor_id) { - _server.EnableForROS(sensor_id); + void SetROS2TopicVisibilityDefaultEnabled(bool _topic_visibility_default_enabled) { + _server.SetROS2TopicVisibilityDefaultEnabled(_topic_visibility_default_enabled); } - void DisableForROS(stream_id sensor_id) { - _server.DisableForROS(sensor_id); + void EnableForROS(detail::stream_actor_id_type stream_actor_id) { + _server.EnableForROS(stream_actor_id); } - bool IsEnabledForROS(stream_id sensor_id) { - return _server.IsEnabledForROS(sensor_id); + void DisableForROS(detail::stream_actor_id_type stream_actor_id) { + _server.DisableForROS(stream_actor_id); + } + + bool IsEnabledForROS(detail::stream_actor_id_type stream_actor_id) { + return _server.IsEnabledForROS(stream_actor_id); + } + + std::shared_ptr GetDispatcher() const { + return _server.GetDispatcher(); } private: diff --git a/LibCarla/source/carla/streaming/detail/Dispatcher.cpp b/LibCarla/source/carla/streaming/detail/Dispatcher.cpp index da25b2fd029..e4faa3d0124 100644 --- a/LibCarla/source/carla/streaming/detail/Dispatcher.cpp +++ b/LibCarla/source/carla/streaming/detail/Dispatcher.cpp @@ -47,6 +47,9 @@ namespace detail { if (!result.second) { throw_exception(std::runtime_error("failed to create stream!")); } + if ( _topic_visibility_default_enabled ) { + ptr->EnableForROS(0); + } log_debug("Stream created"); return carla::streaming::Stream(ptr); } else { @@ -103,27 +106,27 @@ namespace detail { } } - token_type Dispatcher::GetToken(stream_id_type sensor_id) { + token_type Dispatcher::GetToken(stream_id_type stream_id) { std::lock_guard lock(_mutex); - log_debug("Searching sensor id: ", sensor_id); - auto search = _stream_map.find(sensor_id); + log_debug("Searching sensor id: ", stream_id); + auto search = _stream_map.find(stream_id); if (search != _stream_map.end()) { - log_debug("Found sensor id: ", sensor_id); + log_debug("Found sensor id: ", stream_id); auto stream_state = search->second; stream_state->ForceActive(); - log_debug("Getting token from stream ", sensor_id, " on port ", stream_state->token().get_port()); + log_debug("Getting token from stream ", stream_id, " on port ", stream_state->token().get_port()); return stream_state->token(); } else { - log_debug("Not Found sensor id, creating sensor stream: ", sensor_id); + log_debug("Not Found sensor id, creating sensor stream: ", stream_id); token_type temp_token(_cached_token); - temp_token.set_stream_id(sensor_id); + temp_token.set_stream_id(stream_id); auto ptr = std::make_shared(temp_token); auto result = _stream_map.emplace(std::make_pair(temp_token.get_stream_id(), ptr)); ptr->ForceActive(); if (!result.second) { - log_debug("Failed to create multistream for stream ", sensor_id, " on port ", temp_token.get_port()); + log_debug("Failed to create multistream for stream ", stream_id, " on port ", temp_token.get_port()); } - log_debug("Created token from stream ", sensor_id, " on port ", temp_token.get_port()); + log_debug("Created token from stream ", stream_id, " on port ", temp_token.get_port()); return temp_token; } return token_type(); diff --git a/LibCarla/source/carla/streaming/detail/Dispatcher.h b/LibCarla/source/carla/streaming/detail/Dispatcher.h index 7eea9916fb3..81fbc0c87ac 100644 --- a/LibCarla/source/carla/streaming/detail/Dispatcher.h +++ b/LibCarla/source/carla/streaming/detail/Dispatcher.h @@ -41,26 +41,30 @@ namespace detail { void DeregisterSession(std::shared_ptr session); - token_type GetToken(stream_id_type sensor_id); + token_type GetToken(stream_id_type stream_id); - void EnableForROS(stream_id_type sensor_id) { - auto search = _stream_map.find(sensor_id); + void SetROS2TopicVisibilityDefaultEnabled(bool _topic_visibility_default_enabled) { + _topic_visibility_default_enabled = _topic_visibility_default_enabled; + } + + void EnableForROS(stream_actor_id_type stream_actor_id) { + auto search = _stream_map.find(stream_actor_id.stream_id); if (search != _stream_map.end()) { - search->second->EnableForROS(); + search->second->EnableForROS(stream_actor_id.actor_id); } } - void DisableForROS(stream_id_type sensor_id) { - auto search = _stream_map.find(sensor_id); + void DisableForROS(stream_actor_id_type stream_actor_id) { + auto search = _stream_map.find(stream_actor_id.stream_id); if (search != _stream_map.end()) { - search->second->DisableForROS(); + search->second->DisableForROS(stream_actor_id.actor_id); } } - bool IsEnabledForROS(stream_id_type sensor_id) { - auto search = _stream_map.find(sensor_id); + bool IsEnabledForROS(stream_actor_id_type stream_actor_id) { + auto search = _stream_map.find(stream_actor_id.stream_id); if (search != _stream_map.end()) { - return search->second->IsEnabledForROS(); + return search->second->IsEnabledForROS(stream_actor_id.actor_id); } return false; } @@ -74,6 +78,8 @@ namespace detail { token_type _cached_token; StreamMap _stream_map; + + bool _topic_visibility_default_enabled{false}; }; } // namespace detail diff --git a/LibCarla/source/carla/streaming/detail/tcp/Message.h b/LibCarla/source/carla/streaming/detail/Message.h similarity index 94% rename from LibCarla/source/carla/streaming/detail/tcp/Message.h rename to LibCarla/source/carla/streaming/detail/Message.h index e5ee4ecd71b..245cca7f9a5 100644 --- a/LibCarla/source/carla/streaming/detail/tcp/Message.h +++ b/LibCarla/source/carla/streaming/detail/Message.h @@ -24,7 +24,6 @@ namespace carla { namespace streaming { namespace detail { -namespace tcp { /// Serialization of a set of buffers to be sent over a TCP socket as a single /// message. Template paramenter @a MaxNumberOfBuffers imposes a compile-time @@ -76,6 +75,10 @@ namespace tcp { return MakeListView(begin, begin + _number_of_buffers + 1u); } + auto GetBufferViewSequence() const { + auto begin = _buffers.begin(); + return MakeListView(begin, begin + _number_of_buffers); + } private: message_size_type _number_of_buffers = 0u; @@ -91,7 +94,6 @@ namespace tcp { /// header and body sort of messages. using Message = MessageTmpl<2u>; -} // namespace tcp } // namespace detail } // namespace streaming } // namespace carla diff --git a/LibCarla/source/carla/streaming/detail/MultiStreamState.h b/LibCarla/source/carla/streaming/detail/MultiStreamState.h index d10bbe6647e..928b041367c 100644 --- a/LibCarla/source/carla/streaming/detail/MultiStreamState.h +++ b/LibCarla/source/carla/streaming/detail/MultiStreamState.h @@ -8,12 +8,13 @@ #include "carla/AtomicSharedPtr.h" #include "carla/Logging.h" +#include "carla/streaming/detail/Message.h" #include "carla/streaming/detail/StreamStateBase.h" -#include "carla/streaming/detail/tcp/Message.h" +#include #include #include -#include +#include namespace carla { namespace streaming { @@ -24,13 +25,9 @@ namespace detail { /// @todo Lacking some optimization. class MultiStreamState final : public StreamStateBase { public: - using StreamStateBase::StreamStateBase; - MultiStreamState(const token_type &token) : - StreamStateBase(token), - _session(nullptr) - {}; + MultiStreamState(const token_type &token) : StreamStateBase(token), _session(nullptr){}; template void Write(Buffers... buffers) { @@ -38,8 +35,8 @@ namespace detail { auto session = _session.load(); if (session != nullptr) { auto message = Session::MakeMessage(buffers...); - session->Write(std::move(message)); - log_debug("sensor ", session->get_stream_id()," data sent"); + session->WriteMessage(std::move(message)); + log_debug("sensor ", session->get_stream_id(), " data sent"); // Return here, _session is only valid if we have a // single session. return; @@ -51,9 +48,9 @@ namespace detail { auto message = Session::MakeMessage(buffers...); for (auto &s : _sessions) { if (s != nullptr) { - s->Write(message); - log_debug("sensor ", s->get_stream_id()," data sent "); - } + s->WriteMessage(message); + log_debug("sensor ", s->get_stream_id(), " data sent "); + } } } } @@ -62,25 +59,48 @@ namespace detail { _force_active = true; } - void EnableForROS() { - _enabled_for_ros = true; + void EnableForROS(actor_id_type actor_id) { + log_error("MultiStreamState enable for ros. Searching sessions."); + _enable_for_ros.insert(actor_id); + for (auto &s : _sessions) { + if (s != nullptr) { + s->EnableForROS(actor_id); + log_error("sensor ", s->get_stream_id(), " enable for ros "); + } + } } - void DisableForROS() { - _enabled_for_ros = false; + void DisableForROS(actor_id_type actor_id) { + _enable_for_ros.erase(actor_id); + for (auto &s : _sessions) { + if (s != nullptr) { + s->DisableForROS(actor_id); + log_error("sensor ", s->get_stream_id(), " disable for ros "); + } + } } - bool IsEnabledForROS() { - return _enabled_for_ros; + bool IsEnabledForROS(actor_id_type actor_id) { + for (auto &s : _sessions) { + if (s != nullptr) { + if (s->IsEnabledForROS(actor_id)) { + return true; + } + } + } + return false; } bool AreClientsListening() { - return (_sessions.size() > 0 || _force_active || _enabled_for_ros); + return (_sessions.size() > 0 || _force_active); } void ConnectSession(std::shared_ptr session) final { DEBUG_ASSERT(session != nullptr); std::lock_guard lock(_mutex); + for (auto actor_id: _enable_for_ros) { + session->EnableForROS(actor_id); + } _sessions.emplace_back(std::move(session)); log_debug("Connecting multistream sessions:", _sessions.size()); if (_sessions.size() == 1) { @@ -137,10 +157,10 @@ namespace detail { AtomicSharedPtr _session; // if there are more than one session, we use vector of sessions with mutex std::vector> _sessions; - bool _force_active {false}; - bool _enabled_for_ros {false}; + bool _force_active{false}; + std::set _enable_for_ros; }; -} // namespace detail -} // namespace streaming -} // namespace carla +} // namespace detail +} // namespace streaming +} // namespace carla diff --git a/LibCarla/source/carla/streaming/detail/Session.h b/LibCarla/source/carla/streaming/detail/Session.h index 9ecba74d797..3d7809c94a3 100644 --- a/LibCarla/source/carla/streaming/detail/Session.h +++ b/LibCarla/source/carla/streaming/detail/Session.h @@ -6,13 +6,62 @@ #pragma once -#include "carla/streaming/detail/tcp/ServerSession.h" +#include +#include + +#include "carla/TypeTraits.h" +#include "carla/NonCopyable.h" +#include "carla/streaming/detail/Message.h" +#include "carla/streaming/detail/Types.h" namespace carla { namespace streaming { namespace detail { - using Session = tcp::ServerSession; + /// A base class of a server session. When a session opens, it reads from the socket a + /// stream id object and passes itself to the callback functor. The session + /// closes itself after @a timeout of inactivity is met. + class Session: + private NonCopyable { + + public: + Session(stream_id_type stream_id = 0) :_stream_id(stream_id) {} + virtual ~Session() = default; + + template + static auto MakeMessage(Buffers... buffers) { + static_assert( + are_same::value, + "This function only accepts arguments of type BufferView."); + return std::make_shared(buffers...); + + } + + /// @warning This function should only be called after the session is + /// opened. It is safe to call this function from within the @a callback. + stream_id_type get_stream_id() const { + return _stream_id; + } + + /// Writes message to the socket. + virtual void WriteMessage(std::shared_ptr message) = 0; + + /// Writes some data to the socket. + template + void Write(Buffers... buffers) { + WriteMessage(MakeMessage(buffers...)); + } + + /// Post a job to close the session. + virtual void Close() = 0; + + virtual void EnableForROS(actor_id_type actor_id) { (void) actor_id; } + virtual void DisableForROS(actor_id_type actor_id) { (void) actor_id; } + virtual bool IsEnabledForROS(actor_id_type actor_id) { (void) actor_id; return false; } + + protected: + stream_id_type _stream_id = 0u; + }; } // namespace detail } // namespace streaming diff --git a/LibCarla/source/carla/streaming/detail/Stream.h b/LibCarla/source/carla/streaming/detail/Stream.h index d371479f1c6..d6582105b01 100644 --- a/LibCarla/source/carla/streaming/detail/Stream.h +++ b/LibCarla/source/carla/streaming/detail/Stream.h @@ -67,6 +67,7 @@ namespace detail { return _shared_state ? _shared_state->AreClientsListening() : false; } + private: friend class detail::Dispatcher; diff --git a/LibCarla/source/carla/streaming/detail/Types.h b/LibCarla/source/carla/streaming/detail/Types.h index a8401f9dc7d..3d119e50afb 100644 --- a/LibCarla/source/carla/streaming/detail/Types.h +++ b/LibCarla/source/carla/streaming/detail/Types.h @@ -19,6 +19,13 @@ namespace detail { using message_size_type = uint32_t; + using actor_id_type = uint32_t; + + struct stream_actor_id_type { + stream_id_type stream_id; + actor_id_type actor_id; + }; + static_assert( std::is_same::value, "uint type mismatch!"); diff --git a/LibCarla/source/carla/streaming/detail/tcp/ServerSession.cpp b/LibCarla/source/carla/streaming/detail/tcp/ServerSession.cpp index 38dee424d42..a4545690ee7 100644 --- a/LibCarla/source/carla/streaming/detail/tcp/ServerSession.cpp +++ b/LibCarla/source/carla/streaming/detail/tcp/ServerSession.cpp @@ -76,7 +76,7 @@ namespace tcp { }); } - void ServerSession::Write(std::shared_ptr message) { + void ServerSession::WriteMessage(std::shared_ptr message) { DEBUG_ASSERT(message != nullptr); DEBUG_ASSERT(!message->empty()); auto self = shared_from_this(); diff --git a/LibCarla/source/carla/streaming/detail/tcp/ServerSession.h b/LibCarla/source/carla/streaming/detail/tcp/ServerSession.h index 7827b93c327..753861cc034 100644 --- a/LibCarla/source/carla/streaming/detail/tcp/ServerSession.h +++ b/LibCarla/source/carla/streaming/detail/tcp/ServerSession.h @@ -6,12 +6,9 @@ #pragma once -#include "carla/NonCopyable.h" #include "carla/Time.h" -#include "carla/TypeTraits.h" #include "carla/profiler/LifetimeProfiled.h" -#include "carla/streaming/detail/Types.h" -#include "carla/streaming/detail/tcp/Message.h" +#include "carla/streaming/detail/Session.h" #if defined(__clang__) # pragma clang diagnostic push @@ -25,9 +22,6 @@ # pragma clang diagnostic pop #endif -#include -#include - namespace carla { namespace streaming { namespace detail { @@ -40,8 +34,8 @@ namespace tcp { /// closes itself after @a timeout of inactivity is met. class ServerSession : public std::enable_shared_from_this, - private profiler::LifetimeProfiled, - private NonCopyable { + public Session, + private profiler::LifetimeProfiled { public: using socket_type = boost::asio::ip::tcp::socket; @@ -58,31 +52,11 @@ namespace tcp { callback_function_type on_opened, callback_function_type on_closed); - /// @warning This function should only be called after the session is - /// opened. It is safe to call this function from within the @a callback. - stream_id_type get_stream_id() const { - return _stream_id; - } - - template - static auto MakeMessage(Buffers... buffers) { - static_assert( - are_same::value, - "This function only accepts arguments of type BufferView."); - return std::make_shared(buffers...); - } - - /// Writes some data to the socket. - void Write(std::shared_ptr message); - - /// Writes some data to the socket. - template - void Write(Buffers... buffers) { - Write(MakeMessage(buffers...)); - } + /// Writes message to the socket. + virtual void WriteMessage(std::shared_ptr message) override; /// Post a job to close the session. - void Close(); + virtual void Close() override; private: @@ -96,8 +70,6 @@ namespace tcp { const size_t _session_id; - stream_id_type _stream_id = 0u; - socket_type _socket; time_duration _timeout; diff --git a/LibCarla/source/carla/streaming/low_level/Server.h b/LibCarla/source/carla/streaming/low_level/Server.h index 9025d2c726d..3d7948c0a94 100644 --- a/LibCarla/source/carla/streaming/low_level/Server.h +++ b/LibCarla/source/carla/streaming/low_level/Server.h @@ -40,7 +40,7 @@ namespace low_level { detail::EndPoint internal_ep, detail::EndPoint external_ep) : _server(io_context, std::move(internal_ep)), - _dispatcher(std::move(external_ep)) { + _dispatcher(std::make_shared(std::move(external_ep))) { StartServer(); } @@ -49,7 +49,7 @@ namespace low_level { boost::asio::io_context &io_context, detail::EndPoint internal_ep) : _server(io_context, std::move(internal_ep)), - _dispatcher(make_endpoint(_server.GetLocalEndpoint().port())) { + _dispatcher(std::make_shared(make_endpoint(_server.GetLocalEndpoint().port()))) { StartServer(); } @@ -66,51 +66,59 @@ namespace low_level { } Stream MakeStream() { - return _dispatcher.MakeStream(); + return _dispatcher->MakeStream(); } void CloseStream(carla::streaming::detail::stream_id_type id) { - return _dispatcher.CloseStream(id); + return _dispatcher->CloseStream(id); } void SetSynchronousMode(bool is_synchro) { _server.SetSynchronousMode(is_synchro); } - token_type GetToken(stream_id sensor_id) { - return _dispatcher.GetToken(sensor_id); + token_type GetToken(stream_id stream_id) { + return _dispatcher->GetToken(stream_id); } - void EnableForROS(stream_id sensor_id) { - _dispatcher.EnableForROS(sensor_id); + void SetROS2TopicVisibilityDefaultEnabled(bool _topic_visibility_default_enabled) { + _dispatcher->SetROS2TopicVisibilityDefaultEnabled(_topic_visibility_default_enabled); + } + + void EnableForROS(detail::stream_actor_id_type stream_actor_id) { + _dispatcher->EnableForROS(stream_actor_id); + } + + void DisableForROS(detail::stream_actor_id_type stream_actor_id) { + _dispatcher->DisableForROS(stream_actor_id); } - void DisableForROS(stream_id sensor_id) { - _dispatcher.DisableForROS(sensor_id); + bool IsEnabledForROS(detail::stream_actor_id_type stream_actor_id) { + return _dispatcher->IsEnabledForROS(stream_actor_id); } - bool IsEnabledForROS(stream_id sensor_id) { - return _dispatcher.IsEnabledForROS(sensor_id); + std::shared_ptr GetDispatcher() const { + return _dispatcher; } private: void StartServer() { auto on_session_opened = [this](auto session) { - if (!_dispatcher.RegisterSession(session)) { + if (!_dispatcher->RegisterSession(session)) { session->Close(); } }; auto on_session_closed = [this](auto session) { log_debug("on_session_closed called"); - _dispatcher.DeregisterSession(session); + _dispatcher->DeregisterSession(session); }; _server.Listen(on_session_opened, on_session_closed); } underlying_server _server; - detail::Dispatcher _dispatcher; + std::shared_ptr _dispatcher; }; } // namespace low_level diff --git a/LibCarla/source/carla/trafficmanager/CollisionStage.cpp b/LibCarla/source/carla/trafficmanager/CollisionStage.cpp index 11c494bfa74..b0e23fe5cfc 100644 --- a/LibCarla/source/carla/trafficmanager/CollisionStage.cpp +++ b/LibCarla/source/carla/trafficmanager/CollisionStage.cpp @@ -154,7 +154,7 @@ LocationVector CollisionStage::GetBoundary(const ActorId actor_id) { float bbox_y = dimensions.y; const cg::Vector3D x_boundary_vector = heading_vector * (bbox_x + forward_extension); - const auto perpendicular_vector = cg::Vector3D(-heading_vector.y, heading_vector.x, 0.0f).MakeSafeUnitVector(EPSILON); + const auto perpendicular_vector = cg::Vector3D(-heading_vector.y, heading_vector.x, 0.0f).MakeUnitVector(EPSILON); const cg::Vector3D y_boundary_vector = perpendicular_vector * (bbox_y + forward_extension); // Four corners of the vehicle in top view clockwise order (left-handed system). @@ -210,7 +210,7 @@ LocationVector CollisionStage::GetGeodesicBoundary(const ActorId actor_id) { const cg::Vector3D heading_vector = current_point->GetForwardVector(); const cg::Location location = current_point->GetLocation(); cg::Vector3D perpendicular_vector = cg::Vector3D(-heading_vector.y, heading_vector.x, 0.0f); - perpendicular_vector = perpendicular_vector.MakeSafeUnitVector(EPSILON); + perpendicular_vector = perpendicular_vector.MakeUnitVector(EPSILON); // Direction determined for the left-handed system. const cg::Vector3D scaled_perpendicular = perpendicular_vector * width; left_boundary.push_back(location + cg::Location(scaled_perpendicular)); @@ -316,13 +316,13 @@ std::pair CollisionStage::NegotiateCollision(const ActorId referenc const cg::Vector3D reference_heading = simulation_state.GetHeading(reference_vehicle_id); // Vector from ego position to position of the other vehicle. cg::Vector3D reference_to_other = other_location - reference_location; - reference_to_other = reference_to_other.MakeSafeUnitVector(EPSILON); + reference_to_other = reference_to_other.MakeUnitVector(EPSILON); // Other vehicle heading. const cg::Vector3D other_heading = simulation_state.GetHeading(other_actor_id); // Vector from other vehicle position to ego position. cg::Vector3D other_to_reference = reference_location - other_location; - other_to_reference = other_to_reference.MakeSafeUnitVector(EPSILON); + other_to_reference = other_to_reference.MakeUnitVector(EPSILON); float reference_vehicle_length = simulation_state.GetDimensions(reference_vehicle_id).x * SQUARE_ROOT_OF_TWO; float other_vehicle_length = simulation_state.GetDimensions(other_actor_id).x * SQUARE_ROOT_OF_TWO; diff --git a/LibCarla/source/carla/trafficmanager/InMemoryMap.cpp b/LibCarla/source/carla/trafficmanager/InMemoryMap.cpp index 8fc8f304fe0..f03b11f5195 100644 --- a/LibCarla/source/carla/trafficmanager/InMemoryMap.cpp +++ b/LibCarla/source/carla/trafficmanager/InMemoryMap.cpp @@ -245,8 +245,8 @@ namespace traffic_manager { auto compare_s = [](const SimpleWaypointPtr &swp1, const SimpleWaypointPtr &swp2) { return (swp1->GetWaypoint()->GetDistance() < swp2->GetWaypoint()->GetDistance()); }; - auto wpt_angle = [](cg::Vector3D l1, cg::Vector3D l2) { - return cg::Math::GetVectorAngle(l1, l2); + auto wpt_angle_abs = [](cg::Vector3D l1, cg::Vector3D l2) { + return cg::Math::GetVectorAngleAbs(l1, l2); }; auto max = [](int16_t x, int16_t y) { return x ^ ((x ^ y) & -(x < y)); @@ -269,8 +269,8 @@ namespace traffic_manager { // Adding more waypoints if the angle is too tight or if they are too distant. for (std::size_t i = 0; i < segment_waypoints.size() - 1; ++i) { double distance = std::abs(segment_waypoints.at(i)->GetWaypoint()->GetDistance() - segment_waypoints.at(i+1)->GetWaypoint()->GetDistance()); - double angle = wpt_angle(segment_waypoints.at(i)->GetTransform().GetForwardVector(), segment_waypoints.at(i+1)->GetTransform().GetForwardVector()); - int16_t angle_splits = static_cast(angle/MAX_WPT_RADIANS); + double angle_abs = wpt_angle_abs(segment_waypoints.at(i)->GetTransform().GetForwardVector(), segment_waypoints.at(i+1)->GetTransform().GetForwardVector()); + int16_t angle_splits = static_cast(angle_abs/MAX_WPT_RADIANS); int16_t distance_splits = static_cast((distance*distance)/MAX_WPT_DISTANCE); auto max_splits = max(angle_splits, distance_splits); if (max_splits >= 1) { diff --git a/LibCarla/source/carla/trafficmanager/LocalizationUtils.cpp b/LibCarla/source/carla/trafficmanager/LocalizationUtils.cpp index 8e3cad3939f..df35b4f1d4c 100644 --- a/LibCarla/source/carla/trafficmanager/LocalizationUtils.cpp +++ b/LibCarla/source/carla/trafficmanager/LocalizationUtils.cpp @@ -17,8 +17,13 @@ float DeviationCrossProduct(const cg::Location &reference_location, const cg::Vector3D &heading_vector, const cg::Location &target_location) { cg::Vector3D next_vector = target_location - reference_location; - next_vector = next_vector.MakeSafeUnitVector(EPSILON); - const float cross_z = heading_vector.x * next_vector.y - heading_vector.y * next_vector.x; + auto next_vector_length = next_vector.Length(); + float cross_z = 0.; + if ( next_vector_length > EPSILON ) + { + next_vector = next_vector.MakeUnitVectorLengthInput(EPSILON, next_vector_length); + cross_z = heading_vector.x * next_vector.y - heading_vector.y * next_vector.x; + } return cross_z; } @@ -27,11 +32,16 @@ float DeviationDotProduct(const cg::Location &reference_location, const cg::Location &target_location) { cg::Vector3D next_vector = target_location - reference_location; next_vector.z = 0.0f; - next_vector = next_vector.MakeSafeUnitVector(EPSILON); - cg::Vector3D heading_vector_flat(heading_vector.x, heading_vector.y, 0); - heading_vector_flat = heading_vector_flat.MakeSafeUnitVector(EPSILON); - float dot_product = cg::Math::Dot(next_vector, heading_vector_flat); - dot_product = std::max(0.0f, std::min(dot_product, 1.0f)); + auto next_vector_length = next_vector.Length(); + float dot_product = 0.; + if ( next_vector_length > EPSILON ) + { + next_vector = next_vector.MakeUnitVectorLengthInput(EPSILON, next_vector_length); + cg::Vector3D heading_vector_flat(heading_vector.x, heading_vector.y, 0); + heading_vector_flat = heading_vector_flat.MakeUnitVector(EPSILON); + dot_product = cg::Math::Dot(next_vector, heading_vector_flat); + dot_product = std::max(0.0f, std::min(dot_product, 1.0f)); + } return dot_product; } diff --git a/LibCarla/source/carla/trafficmanager/MotionPlanStage.cpp b/LibCarla/source/carla/trafficmanager/MotionPlanStage.cpp index 66bb6176dde..b528e778ca3 100644 --- a/LibCarla/source/carla/trafficmanager/MotionPlanStage.cpp +++ b/LibCarla/source/carla/trafficmanager/MotionPlanStage.cpp @@ -171,17 +171,11 @@ void MotionPlanStage::Update(const unsigned long index) { auto right_vector = target_waypoint->GetTransform().GetRightVector(); auto offset_location = cg::Location(cg::Vector3D(offset*right_vector.x, offset*right_vector.y, 0.0f)); target_location = target_location + offset_location; + auto towards_target_vector = target_location - vehicle_location; + towards_target_vector.z = 0.; + auto angle_delta_rad = cg::Math::GetVectorAngle(vehicle_heading, towards_target_vector); - // Get the targer deviations. - cg::Vector3D target_vector = target_location - vehicle_location; - float target_yaw = std::atan2(target_vector.y, target_vector.x) *180.0f / PI; - float angular_deviation = target_yaw - vehicle_rotation.yaw; - if (angular_deviation > 180.0f) { - angular_deviation = angular_deviation - 360.0f; - } else if (angular_deviation < -180.0f) { - angular_deviation = angular_deviation + 360.0f; - } - angular_deviation = angular_deviation / 180.0f; // Between -1 and 1 + const float angular_deviation = angle_delta_rad / PI; const float velocity_deviation = (dynamic_target_velocity - vehicle_speed) / dynamic_target_velocity; // If previous state for vehicle not found, initialize state entry. @@ -255,10 +249,10 @@ void MotionPlanStage::Update(const unsigned long index) { cg::Transform target_base_transform = teleport_target->GetTransform(); cg::Location target_base_location = target_base_transform.location; cg::Vector3D target_heading = target_base_transform.GetForwardVector(); - cg::Vector3D correct_heading = (target_base_location - vehicle_location).MakeSafeUnitVector(EPSILON); + cg::Vector3D correct_heading = (target_base_location - vehicle_location).MakeUnitVector(EPSILON); if (vehicle_location.Distance(target_base_location) < target_displacement) { - cg::Location teleportation_location = vehicle_location + cg::Location(target_heading.MakeSafeUnitVector(EPSILON) * target_displacement); + cg::Location teleportation_location = vehicle_location + cg::Location(target_heading.MakeUnitVector(EPSILON) * target_displacement); teleportation_transform = cg::Transform(teleportation_location, target_base_transform.rotation); } else { diff --git a/LibCarla/source/test/common/test_geom.cpp b/LibCarla/source/test/common/test_geom.cpp index 994bdcbfaa8..e8c8a0637dd 100644 --- a/LibCarla/source/test/common/test_geom.cpp +++ b/LibCarla/source/test/common/test_geom.cpp @@ -10,6 +10,7 @@ #include #include #include +#include #include namespace carla { @@ -104,20 +105,175 @@ TEST(geom, bbox_get_local_vertices_get_world_vertices_coherence) { } } +TEST(geom, quaternion_get_yaw) { + constexpr double error = 0.001; + + { Rotation rotation (0.0,90.0,0.0); // y z x + Quaternion quat(rotation); + auto const yaw = quat.YawDegree(); + + ASSERT_NEAR(yaw, 90.f, error) << "quat: " << quat.x << " " << quat.y << " " << quat.z << " " << quat.w; + } + { + Rotation rotation (11.0,33.0,55.0); // y z x + Quaternion quat(rotation); + auto const yaw = quat.YawDegree(); + + ASSERT_NEAR(yaw, 33.f, error) << "quat: " << quat.x << " " << quat.y << " " << quat.z << " " << quat.w; + } +} -TEST(geom, single_point_rotation) { +TEST(geom, quaternion_inverse) { constexpr double error = 0.001; - Location translation (0.0,0.0,0.0); - Rotation rotation (0.0,180.0,0.0); // y z x - Transform transform (translation, rotation); + Rotation rotation (11.0,33.0,55.0); // y z x + Quaternion quat(rotation); + auto const inverse = quat.Inverse(); + auto const unit = quat * inverse; + ASSERT_NEAR(unit.x, Quaternion().x, error) << "unit: " << unit.x << " " << unit.y << " " << unit.z << " " << unit.w; + ASSERT_NEAR(unit.y, Quaternion().y, error) << "unit: " << unit.x << " " << unit.y << " " << unit.z << " " << unit.w; + ASSERT_NEAR(unit.z, Quaternion().z, error) << "unit: " << unit.x << " " << unit.y << " " << unit.z << " " << unit.w; + ASSERT_NEAR(unit.w, Quaternion().w, error) << "unit: " << unit.x << " " << unit.y << " " << unit.z << " " << unit.w; +} - Location point (0.0, 0.0, 1.0); - transform.TransformPoint(point); - Location result_point(0.0, 0.0, 1.0); - ASSERT_NEAR(point.x, result_point.x, error); - ASSERT_NEAR(point.y, result_point.y, error); - ASSERT_NEAR(point.z, result_point.z, error); +Vector3D carla_0_9_15_RotatedVector(Rotation const &rotator, Vector3D const &in_point) { + // Rotates Rz(yaw) * Ry(pitch) * Rx(roll) = first x, then y, then z. + const float cy = std::cos(Math::ToRadians(rotator.yaw)); + const float sy = std::sin(Math::ToRadians(rotator.yaw)); + const float cr = std::cos(Math::ToRadians(rotator.roll)); + const float sr = std::sin(Math::ToRadians(rotator.roll)); + const float cp = std::cos(Math::ToRadians(rotator.pitch)); + const float sp = std::sin(Math::ToRadians(rotator.pitch)); + + Vector3D out_point; + out_point.x = + in_point.x * (cp * cy) + + in_point.y * (cy * sp * sr - sy * cr) + + in_point.z * (-cy * sp * cr - sy * sr); + + out_point.y = + in_point.x * (cp * sy) + + in_point.y * (sy * sp * sr + cy * cr) + + in_point.z * (-sy * sp * cr + cy * sr); + + out_point.z = + in_point.x * (sp) + + in_point.y * (-cp * sr) + + in_point.z * (cp * cr); + + return out_point; +} + +TEST(geom, single_point_rotation_90) { + auto compare = [](int line, Rotation const &rotator, Vector3D point, Vector3D const &result_point)->void { + constexpr double error = 0.001; + + Vector3D const in_point = point; + + Location translation (0.0,0.0,0.0); + Transform transform = Transform(translation, rotator); + transform.TransformPoint(point); + EXPECT_NEAR(point.x, result_point.x, error) + << " LINE " << line << " x: \n" + << " point: " << point.x << " " << point.y << " " << point.z; + EXPECT_NEAR(point.y, result_point.y, error) + << " LINE "<< line << " y: \n" + << " point: " << point.x << " " << point.y << " " << point.z; + EXPECT_NEAR(point.z, result_point.z, error) + << " LINE "<< line << " z: \n" + << " point: " << point.x << " " << point.y << " " << point.z; + + transform.InverseTransformPoint(point); + EXPECT_NEAR(point.x, in_point.x, error) + << " LINE " << line << " -x: \n" + << " point: " << point.x << " " << point.y << " " << point.z; + EXPECT_NEAR(point.y, in_point.y, error) + << " LINE "<< line << " -y: \n" + << " point: " << point.x << " " << point.y << " " << point.z; + EXPECT_NEAR(point.z, in_point.z, error) + << " LINE "<< line << " -z: \n" + << " point: " << point.x << " " << point.y << " " << point.z; + + Quaternion quaternion(rotator); + Vector3D rotated_vector = quaternion.RotatedVector(in_point); + EXPECT_NEAR(rotated_vector.x, result_point.x, error) + << " LINE " << line << " x: \n" + << " quat: " << quaternion.x << " " << quaternion.y << " " << quaternion.z << " " << quaternion.w << "\n" + << " rotated_vector: " << rotated_vector.x << " " << rotated_vector.y << " " << rotated_vector.z; + EXPECT_NEAR(rotated_vector.y, result_point.y, error) + << " LINE "<< line << " y: \n" + << " quat: " << quaternion.x << " " << quaternion.y << " " << quaternion.z << " " << quaternion.w << "\n" + << " rotated_vector: " << rotated_vector.x << " " << rotated_vector.y << " " << rotated_vector.z; + EXPECT_NEAR(rotated_vector.z, result_point.z, error) + << " LINE "<< line << " z: \n" + << " quat: " << quaternion.x << " " << quaternion.y << " " << quaternion.z << " " << quaternion.w << "\n" + << " rotated_vector: " << rotated_vector.x << " " << rotated_vector.y << " " << rotated_vector.z; + rotated_vector = quaternion.InverseRotatedVector(rotated_vector); + EXPECT_NEAR(rotated_vector.x, in_point.x, error) + << " LINE " << line << " -x: \n" + << " quat: " << quaternion.x << " " << quaternion.y << " " << quaternion.z << " " << quaternion.w << "\n" + << " rotated_vector: " << rotated_vector.x << " " << rotated_vector.y << " " << rotated_vector.z; + EXPECT_NEAR(rotated_vector.y, in_point.y, error) + << " LINE "<< line << " -y: \n" + << " quat: " << quaternion.x << " " << quaternion.y << " " << quaternion.z << " " << quaternion.w << "\n" + << " rotated_vector: " << rotated_vector.x << " " << rotated_vector.y << " " << rotated_vector.z; + EXPECT_NEAR(rotated_vector.z, in_point.z, error) + << " LINE "<< line << " -z: \n" + << " quat: " << quaternion.x << " " << quaternion.y << " " << quaternion.z << " " << quaternion.w << "\n" + << " rotated_vector: " << rotated_vector.x << " " << rotated_vector.y << " " << rotated_vector.z; + + auto const carla_0_9_15_result = carla_0_9_15_RotatedVector(rotator, in_point); + if ((std::fabs(carla_0_9_15_result.x-result_point.x) > error) || + (std::fabs(carla_0_9_15_result.y-result_point.y) > error) || + (std::fabs(carla_0_9_15_result.z-result_point.z) > error)) { + std::cerr << "Information: Rotation carla 0.9.16 test Rotation(pitch=" << rotator.pitch << ", yaw=" << rotator.yaw << ", roll=" << rotator.roll << ")" << std::endl + << " point: " << point.x << " " << point.y << " " << point.z << std::endl + << " resulted in point: " << carla_0_9_15_result.x << " " << carla_0_9_15_result.y << " " << carla_0_9_15_result.z << std::endl + << " but correct result is : " << result_point.x << " " << result_point.y << " " << result_point.z << std::endl; + } + }; + + // test all 90° rotations of positive unit vectors on axis; Remember: + // UE uses left-handed coordinate system! + // Because nearly every writing on this is written in a form which let's room for interpretation + // Even that one talks on clock-wise rotation: https://forums.unrealengine.com/t/ue4-coordinate-system-not-right-handed/80398/4, + // but it is not telling if you are watching into axis positive direction or negative direction; therefore "clockwise" can be interpreted in both ways. + // Ok, the example given makes it definitely clear then, which is our test 7 below. + // + // Therefore let's take the easiest way to explain: Your left hand! + // Point thumb upwards (positive z-Axis direction), index finger forwards (positive x-Axis direction), middle finger rightwards (positive y-Axis direction) + // Positive rotation can be "visualized" with thumb of the left hand pointing into the respective positive direction of the rotation axis, + // then the fingers when creating a fist are showing the positive rotation direction. + // + // The same by the way, works for right-handed coordinate systems: just take the right hand instead, resulting in the y-axis beeing flipped and rotation direction switches! + // + // pitch(y) yaw(z) roll(x) px py pz r_x r_y r_z + // pitch hand index finger goes down + compare( 1, { 90.0f, 0.0f, 0.0f}, {1.0f, 0.f, 0.f}, { 0.0f, 0.0f, -1.0f}); // x-axis downwards + compare( 2, { 90.0f, 0.0f, 0.0f}, {0.0f, 1.f, 0.f}, { 0.0f, 1.0f, 0.0f}); // y-axis constant + compare( 3, { 90.0f, 0.0f, 0.0f}, {0.0f, 0.f, 1.f}, { 1.0f, 0.0f, 0.0f}); // z-axis forwards + // pitch hand index finger goes up + compare( 4, { -90.0f, 0.0f, 0.0f}, {1.0f, 0.f, 0.f}, { 0.0f, 0.0f, 1.0f}); // x-axis upwards + compare( 5, { -90.0f, 0.0f, 0.0f}, {0.0f, 1.f, 0.f}, { 0.0f, 1.0f, 0.0f}); // y-axis constant + compare( 6, { -90.0f, 0.0f, 0.0f}, {0.0f, 0.f, 1.f}, {-1.0f, 0.0f, 0.0f}); // z-axis backwards + + // yaw hand index finger goes to the right + compare( 7, { 0.0f, 90.0f, 0.0f}, {1.0f, 0.f, 0.f}, { 0.0f, 1.0f, 0.0f}); // x-axis rightwards + compare( 8, { 0.0f, 90.0f, 0.0f}, {0.0f, 1.f, 0.f}, {-1.0f, 0.0f, 0.0f}); // y-axis backwards + compare( 9, { 0.0f, 90.0f, 0.0f}, {0.0f, 0.f, 1.f}, { 0.0f, 0.0f, 1.0f}); // z-axis constant + // yaw hand index finger goes to the left + compare(10, { 0.0f, -90.0f, 0.0f}, {1.0f, 0.f, 0.f}, { 0.0f, -1.0f, 0.0f}); // x-axis leftwards + compare(11, { 0.0f, -90.0f, 0.0f}, {0.0f, 1.f, 0.f}, { 1.0f, 0.0f, 0.0f}); // y-axis forwards + compare(12, { 0.0f, -90.0f, 0.0f}, {0.0f, 0.f, 1.f}, { 0.0f, 0.0f, 1.0f}); // z-axis constant + + // roll hand: thumb points to the left + compare(13, { 0.0f, 0.0f, 90.0f}, {1.0f, 0.f, 0.f}, { 1.0f, 0.0f, 0.0f}); // x-axis constant + compare(14, { 0.0f, 0.0f, 90.0f}, {0.0f, 1.f, 0.f}, { 0.0f, 0.0f, 1.0f}); // y-axis upwards + compare(15, { 0.0f, 0.0f, 90.0f}, {0.0f, 0.f, 1.f}, { 0.0f, -1.0f, 0.0f}); // z-axis leftwards + // roll hand: thumb points to the right + compare(16, { 0.0f, 0.0f, -90.0f}, {1.0f, 0.f, 0.f}, { 1.0f, 0.0f, 0.0f}); // x-axis constant + compare(17, { 0.0f, 0.0f, -90.0f}, {0.0f, 1.f, 0.f}, { 0.0f, 0.0f, -1.0f}); // y-axis downwards + compare(18, { 0.0f, 0.0f, -90.0f}, {0.0f, 0.f, 1.f}, { 0.0f, 1.0f, 0.0f}); // z-axis rightwards } TEST(geom, single_point_translation_and_rotation) { @@ -129,8 +285,9 @@ TEST(geom, single_point_translation_and_rotation) { Location point (0.0, 0.0, 2.0); transform.TransformPoint(point); - Location result_point(-2.0, 0.0, -1.0); - ASSERT_NEAR(point.x, result_point.x, error); + Location result_point(2.0, 0.0, -1.0); //!!! This line was wrong in CARLA version <= 0.9.16 due to invalid pitch AND roll rotations, (most relevant) yaw rotations were not affected + + ASSERT_NEAR(point.x, result_point.x, error) << point.x << " " << point.y << " " << point.z; ASSERT_NEAR(point.y, result_point.y, error); ASSERT_NEAR(point.z, result_point.z, error); } @@ -205,7 +362,8 @@ TEST(geom, forward_vector) { (std::abs(expected.y - result.y) < eps) && (std::abs(expected.z - result.z) < eps)) << "result = " << result << '\n' - << "expected = " << expected; + << "expected = " << expected << '\n' + << " rotation: " << rotation.roll << " " << rotation.pitch << " " << rotation.yaw; }; // pitch yaw roll x y z compare({ 0.0f, 0.0f, 0.0f}, {1.0f, 0.0f, 0.0f}); @@ -213,7 +371,7 @@ TEST(geom, forward_vector) { compare({360.0f, 360.0f, 0.0f}, {1.0f, 0.0f, 0.0f}); compare({ 0.0f, 90.0f, 0.0f}, {0.0f, 1.0f, 0.0f}); compare({ 0.0f, -90.0f, 0.0f}, {0.0f,-1.0f, 0.0f}); - compare({ 90.0f, 0.0f, 0.0f}, {0.0f, 0.0f, 1.0f}); + compare({ 90.0f, 0.0f, 0.0f}, {0.0f, 0.0f, -1.0f}); //!!! This line was wrong in CARLA version <= 0.9.16 due to invalid pitch AND roll rotations, (most relevant) yaw rotations were not affected compare({180.0f, -90.0f, 0.0f}, {0.0f, 1.0f, 0.0f}); } diff --git a/LibCarla/source/test/common/test_vector3D.cpp b/LibCarla/source/test/common/test_vector3D.cpp index 383e9b9920f..dd4d7a18b55 100644 --- a/LibCarla/source/test/common/test_vector3D.cpp +++ b/LibCarla/source/test/common/test_vector3D.cpp @@ -21,7 +21,7 @@ TEST(vector3D, make_unit_vec) { #ifdef LIBCARLA_NO_EXCEPTIONS ASSERT_DEATH_IF_SUPPORTED( Vector3D().MakeUnitVector(), - "length > 2.0f \\* std::numeric_limits::epsilon()"); + "length >= 2.0f \\* std::numeric_limits::epsilon()"); #else ASSERT_THROW( Vector3D().MakeUnitVector(), diff --git a/PythonAPI/carla/setup.py b/PythonAPI/carla/setup.py index 7c6c802082a..d5caf74372c 100755 --- a/PythonAPI/carla/setup.py +++ b/PythonAPI/carla/setup.py @@ -56,7 +56,7 @@ def walk(folder, file_filter='*'): os.path.join(pwd, 'dependencies/lib/libxerces-c.a')] extra_link_args += ['-lz'] extra_compile_args = [ - '-isystem', os.path.join(pwd, 'dependencies/include/system'), '-fPIC', '-std=c++14', + '-isystem', os.path.join(pwd, 'dependencies/include/system'), '-fPIC', '-std=c++17', '-Werror', '-Wall', '-Wextra', '-Wpedantic', '-Wno-self-assign-overloaded', '-Wdeprecated', '-Wno-shadow', '-Wuninitialized', '-Wunreachable-code', '-Wpessimizing-move', '-Wold-style-cast', '-Wnull-dereference', diff --git a/PythonAPI/carla/source/libcarla/Actor.cpp b/PythonAPI/carla/source/libcarla/Actor.cpp index 98c3aba621d..05e34495f36 100644 --- a/PythonAPI/carla/source/libcarla/Actor.cpp +++ b/PythonAPI/carla/source/libcarla/Actor.cpp @@ -148,6 +148,9 @@ void export_actor() { .def("set_collisions", &cc::Actor::SetCollisions, (arg("enabled") = true)) .def("set_enable_gravity", &cc::Actor::SetEnableGravity, (arg("enabled") = true)) .def("destroy", CALL_WITHOUT_GIL(cc::Actor, Destroy)) + .def("enable_for_ros", &cc::Actor::EnableForROS) + .def("disable_for_ros", &cc::Actor::DisableForROS) + .def("is_enabled_for_ros", &cc::Actor::IsEnabledForROS) .def(self_ns::str(self_ns::self)) ; diff --git a/PythonAPI/carla/source/libcarla/Blueprint.cpp b/PythonAPI/carla/source/libcarla/Blueprint.cpp index 6cbe76e31fc..084f2350fd3 100644 --- a/PythonAPI/carla/source/libcarla/Blueprint.cpp +++ b/PythonAPI/carla/source/libcarla/Blueprint.cpp @@ -4,8 +4,8 @@ // This work is licensed under the terms of the MIT license. // For a copy, see . -#include -#include +#include +#include #include @@ -33,7 +33,7 @@ namespace data { } // namespace data } // namespace sensor -namespace client { +namespace actors { std::ostream &operator<<(std::ostream &out, const ActorAttribute &attr) { using Type = carla::rpc::ActorAttributeType; @@ -74,12 +74,12 @@ namespace client { return PrintList(out, blueprints); } -} // namespace client +} // namespace actors } // namespace carla void export_blueprint() { using namespace boost::python; - namespace cc = carla::client; + namespace ca = carla::actors; namespace crpc = carla::rpc; namespace csd = carla::sensor::data; @@ -124,60 +124,60 @@ void export_blueprint() { .def(self_ns::str(self_ns::self)) ; - class_("ActorAttribute", no_init) - .add_property("id", CALL_RETURNING_COPY(cc::ActorAttribute, GetId)) - .add_property("type", &cc::ActorAttribute::GetType) - .add_property("recommended_values", CALL_RETURNING_LIST(cc::ActorAttribute, GetRecommendedValues)) - .add_property("is_modifiable", &cc::ActorAttribute::IsModifiable) - .def("as_bool", &cc::ActorAttribute::As) - .def("as_int", &cc::ActorAttribute::As) - .def("as_float", &cc::ActorAttribute::As) - .def("as_str", &cc::ActorAttribute::As) - .def("as_color", &cc::ActorAttribute::As) - .def("__eq__", &cc::ActorAttributeValueAccess::operator==) - .def("__eq__", &cc::ActorAttributeValueAccess::operator==) - .def("__eq__", &cc::ActorAttributeValueAccess::operator==) - .def("__eq__", &cc::ActorAttributeValueAccess::operator==) - .def("__eq__", &cc::ActorAttributeValueAccess::operator==) - .def("__eq__", &cc::ActorAttributeValueAccess::operator==) - .def("__ne__", &cc::ActorAttributeValueAccess::operator!=) - .def("__ne__", &cc::ActorAttributeValueAccess::operator!=) - .def("__ne__", &cc::ActorAttributeValueAccess::operator!=) - .def("__ne__", &cc::ActorAttributeValueAccess::operator!=) - .def("__ne__", &cc::ActorAttributeValueAccess::operator!=) - .def("__ne__", &cc::ActorAttributeValueAccess::operator!=) - .def("__nonzero__", &cc::ActorAttribute::As) - .def("__bool__", &cc::ActorAttribute::As) - .def("__int__", &cc::ActorAttribute::As) - .def("__float__", &cc::ActorAttribute::As) - .def("__str__", &cc::ActorAttribute::As) + class_("ActorAttribute", no_init) + .add_property("id", CALL_RETURNING_COPY(ca::ActorAttribute, GetId)) + .add_property("type", &ca::ActorAttribute::GetType) + .add_property("recommended_values", CALL_RETURNING_LIST(ca::ActorAttribute, GetRecommendedValues)) + .add_property("is_modifiable", &ca::ActorAttribute::IsModifiable) + .def("as_bool", &ca::ActorAttribute::As) + .def("as_int", &ca::ActorAttribute::As) + .def("as_float", &ca::ActorAttribute::As) + .def("as_str", &ca::ActorAttribute::As) + .def("as_color", &ca::ActorAttribute::As) + .def("__eq__", &ca::ActorAttributeValueAccess::operator==) + .def("__eq__", &ca::ActorAttributeValueAccess::operator==) + .def("__eq__", &ca::ActorAttributeValueAccess::operator==) + .def("__eq__", &ca::ActorAttributeValueAccess::operator==) + .def("__eq__", &ca::ActorAttributeValueAccess::operator==) + .def("__eq__", &ca::ActorAttributeValueAccess::operator==) + .def("__ne__", &ca::ActorAttributeValueAccess::operator!=) + .def("__ne__", &ca::ActorAttributeValueAccess::operator!=) + .def("__ne__", &ca::ActorAttributeValueAccess::operator!=) + .def("__ne__", &ca::ActorAttributeValueAccess::operator!=) + .def("__ne__", &ca::ActorAttributeValueAccess::operator!=) + .def("__ne__", &ca::ActorAttributeValueAccess::operator!=) + .def("__nonzero__", &ca::ActorAttribute::As) + .def("__bool__", &ca::ActorAttribute::As) + .def("__int__", &ca::ActorAttribute::As) + .def("__float__", &ca::ActorAttribute::As) + .def("__str__", &ca::ActorAttribute::As) .def(self_ns::str(self_ns::self)) ; - class_("ActorBlueprint", no_init) - .add_property("id", CALL_RETURNING_COPY(cc::ActorBlueprint, GetId)) - .add_property("tags", CALL_RETURNING_LIST(cc::ActorBlueprint, GetTags)) - .def("has_tag", &cc::ActorBlueprint::ContainsTag) - .def("match_tags", &cc::ActorBlueprint::MatchTags) - .def("has_attribute", &cc::ActorBlueprint::ContainsAttribute) - .def("get_attribute", CALL_RETURNING_COPY_1(cc::ActorBlueprint, GetAttribute, const std::string &)) - .def("set_attribute", &cc::ActorBlueprint::SetAttribute) - .def("__len__", &cc::ActorBlueprint::size) - .def("__iter__", range(&cc::ActorBlueprint::begin, &cc::ActorBlueprint::end)) + class_("ActorBlueprint", no_init) + .add_property("id", CALL_RETURNING_COPY(ca::ActorBlueprint, GetId)) + .add_property("tags", CALL_RETURNING_LIST(ca::ActorBlueprint, GetTags)) + .def("has_tag", &ca::ActorBlueprint::ContainsTag) + .def("match_tags", &ca::ActorBlueprint::MatchTags) + .def("has_attribute", &ca::ActorBlueprint::ContainsAttribute) + .def("get_attribute", CALL_RETURNING_COPY_1(ca::ActorBlueprint, GetAttribute, const std::string &)) + .def("set_attribute", &ca::ActorBlueprint::SetAttribute) + .def("__len__", &ca::ActorBlueprint::size) + .def("__iter__", range(&ca::ActorBlueprint::begin, &ca::ActorBlueprint::end)) .def(self_ns::str(self_ns::self)) ; - class_>("BlueprintLibrary", no_init) - .def("find", +[](const cc::BlueprintLibrary &self, const std::string &key) -> cc::ActorBlueprint { + class_>("BlueprintLibrary", no_init) + .def("find", +[](const ca::BlueprintLibrary &self, const std::string &key) -> ca::ActorBlueprint { return self.at(key); }, (arg("id"))) - .def("filter", &cc::BlueprintLibrary::Filter, (arg("wildcard_pattern"))) - .def("filter_by_attribute", &cc::BlueprintLibrary::FilterByAttribute, (arg("name"), arg("value"))) - .def("__getitem__", +[](const cc::BlueprintLibrary &self, size_t pos) -> cc::ActorBlueprint { + .def("filter", &ca::BlueprintLibrary::Filter, (arg("wildcard_pattern"))) + .def("filter_by_attribute", &ca::BlueprintLibrary::FilterByAttribute, (arg("name"), arg("value"))) + .def("__getitem__", +[](const ca::BlueprintLibrary &self, size_t pos) -> ca::ActorBlueprint { return self.at(pos); }) - .def("__len__", &cc::BlueprintLibrary::size) - .def("__iter__", range(&cc::BlueprintLibrary::begin, &cc::BlueprintLibrary::end)) + .def("__len__", &ca::BlueprintLibrary::size) + .def("__iter__", range(&ca::BlueprintLibrary::begin, &ca::BlueprintLibrary::end)) .def(self_ns::str(self_ns::self)) ; } diff --git a/PythonAPI/carla/source/libcarla/Commands.cpp b/PythonAPI/carla/source/libcarla/Commands.cpp index 0b794c68a8a..bba825469b8 100644 --- a/PythonAPI/carla/source/libcarla/Commands.cpp +++ b/PythonAPI/carla/source/libcarla/Commands.cpp @@ -21,7 +21,7 @@ namespace command_impl { return actor->GetId(); } - carla::rpc::ActorDescription Convert(const carla::client::ActorBlueprint &blueprint) { + carla::rpc::ActorDescription Convert(const carla::actors::ActorBlueprint &blueprint) { return blueprint.MakeActorDescription(); } @@ -46,6 +46,7 @@ namespace command_impl { void export_commands() { using namespace boost::python; + namespace ca = carla::actors; namespace cc = carla::client; namespace cg = carla::geom; namespace cr = carla::rpc; @@ -72,19 +73,19 @@ void export_commands() { class_("SpawnActor") .def( "__init__", - &command_impl::CustomSpawnActorInit, + &command_impl::CustomSpawnActorInit, (arg("blueprint"), arg("transform"))) .def( "__init__", - &command_impl::CustomSpawnActorInit, + &command_impl::CustomSpawnActorInit, (arg("blueprint"), arg("transform"), arg("parent_id"))) .def( "__init__", - &command_impl::CustomSpawnActorInit, + &command_impl::CustomSpawnActorInit, (arg("blueprint"), arg("transform"), arg("parent"))) .def( "__init__", - &command_impl::CustomSpawnActorInit, + &command_impl::CustomSpawnActorInit, (arg("blueprint"), arg("transform"), arg("parent"), arg("attachment_type"), arg("socket_name"))) .def(init()) .def_readwrite("transform", &cr::Command::SpawnActor::transform) diff --git a/PythonAPI/carla/source/libcarla/Control.cpp b/PythonAPI/carla/source/libcarla/Control.cpp index c39db05a9df..68411c149e6 100644 --- a/PythonAPI/carla/source/libcarla/Control.cpp +++ b/PythonAPI/carla/source/libcarla/Control.cpp @@ -31,7 +31,8 @@ namespace rpc { << ", hand_brake=" << boolalpha(control.hand_brake) << ", reverse=" << boolalpha(control.reverse) << ", manual_gear_shift=" << boolalpha(control.manual_gear_shift) - << ", gear=" << std::to_string(control.gear) << ')'; + << ", gear=" << std::to_string(control.gear) + << ", timestamp=" << std::to_string(control.timestamp) << ')'; return out; } @@ -47,7 +48,8 @@ namespace rpc { std::ostream &operator<<(std::ostream &out, const WalkerControl &control) { out << "WalkerControl(direction=" << control.direction << ", speed=" << std::to_string(control.speed) - << ", jump=" << boolalpha(control.jump) << ')'; + << ", jump=" << boolalpha(control.jump) + << ", timestamp=" << std::to_string(control.timestamp) << ')'; return out; } @@ -393,14 +395,15 @@ void export_control() { namespace cr = carla::rpc; class_("VehicleControl") - .def(init( + .def(init( (arg("throttle") = 0.0f, arg("steer") = 0.0f, arg("brake") = 0.0f, arg("hand_brake") = false, arg("reverse") = false, arg("manual_gear_shift") = false, - arg("gear") = 0))) + arg("gear") = 0, + arg("timestamp") = 0.0f))) .def_readwrite("throttle", &cr::VehicleControl::throttle) .def_readwrite("steer", &cr::VehicleControl::steer) .def_readwrite("brake", &cr::VehicleControl::brake) @@ -408,23 +411,26 @@ void export_control() { .def_readwrite("reverse", &cr::VehicleControl::reverse) .def_readwrite("manual_gear_shift", &cr::VehicleControl::manual_gear_shift) .def_readwrite("gear", &cr::VehicleControl::gear) + .def_readwrite("timestamp", &cr::VehicleControl::timestamp) .def("__eq__", &cr::VehicleControl::operator==) .def("__ne__", &cr::VehicleControl::operator!=) .def(self_ns::str(self_ns::self)) ; class_("VehicleAckermannControl") - .def(init( + .def(init( (arg("steer") = 0.0f, arg("steer_speed") = 0.0f, arg("speed") = 0.0f, arg("acceleration") = 0.0f, - arg("jerk") = 0.0f))) + arg("jerk") = 0.0f, + arg("timestamp") = 0.0f))) .def_readwrite("steer", &cr::VehicleAckermannControl::steer) .def_readwrite("steer_speed", &cr::VehicleAckermannControl::steer_speed) .def_readwrite("speed", &cr::VehicleAckermannControl::speed) .def_readwrite("acceleration", &cr::VehicleAckermannControl::acceleration) .def_readwrite("jerk", &cr::VehicleAckermannControl::jerk) + .def_readwrite("timestamp", &cr::VehicleAckermannControl::timestamp) .def("__eq__", &cr::VehicleAckermannControl::operator==) .def("__ne__", &cr::VehicleAckermannControl::operator!=) .def(self_ns::str(self_ns::self)) @@ -450,13 +456,15 @@ void export_control() { ; class_("WalkerControl") - .def(init( + .def(init( (arg("direction") = cg::Vector3D{1.0f, 0.0f, 0.0f}, arg("speed") = 0.0f, - arg("jump") = false))) + arg("jump") = false, + arg("timestamp") = 0.0f))) .def_readwrite("direction", &cr::WalkerControl::direction) .def_readwrite("speed", &cr::WalkerControl::speed) .def_readwrite("jump", &cr::WalkerControl::jump) + .def_readwrite("timestamp", &cr::WalkerControl::timestamp) .def("__eq__", &cr::WalkerControl::operator==) .def("__ne__", &cr::WalkerControl::operator!=) .def(self_ns::str(self_ns::self)) diff --git a/PythonAPI/carla/source/libcarla/Geom.cpp b/PythonAPI/carla/source/libcarla/Geom.cpp index 4f842cdeb70..064e2227ab4 100644 --- a/PythonAPI/carla/source/libcarla/Geom.cpp +++ b/PythonAPI/carla/source/libcarla/Geom.cpp @@ -7,11 +7,15 @@ #include #include #include +#include +#include #include #include +#include #include #include #include +#include #include #include @@ -51,10 +55,34 @@ namespace geom { return out; } - std::ostream &operator<<(std::ostream &out, const Rotation &rotation) { - out << "Rotation(pitch=" << std::to_string(rotation.pitch) - << ", yaw=" << std::to_string(rotation.yaw) - << ", roll=" << std::to_string(rotation.roll) << ')'; + std::ostream &operator<<(std::ostream &out, const Velocity &vector3D) { + WriteVector3D(out, "Velocity", vector3D); + return out; + } + + std::ostream &operator<<(std::ostream &out, const AngularVelocity &vector3D) { + WriteVector3D(out, "AngularVelocity", vector3D); + return out; + } + + std::ostream &operator<<(std::ostream &out, const Acceleration &vector3D) { + WriteVector3D(out, "Acceleration", vector3D); + return out; + } + + std::ostream &operator<<(std::ostream &out, const Rotation &rotator) { + out << "Rotation(pitch=" << std::to_string(rotator.pitch) + << ", yaw=" << std::to_string(rotator.yaw) + << ", roll=" << std::to_string(rotator.roll) << ')'; + return out; + } + + std::ostream &operator<<(std::ostream &out, const Quaternion &quaternion) { + out << "Quaternion" + << "(x=" << std::to_string(quaternion.x) + << ", y=" << std::to_string(quaternion.y) + << ", z=" << std::to_string(quaternion.z) + << ", w=" << std::to_string(quaternion.w) << ')'; return out; } @@ -88,6 +116,7 @@ static void TransformList(const carla::geom::Transform &self, boost::python::lis } } +#if ALLOW_UNSAFE_GEOM_MATRIX_ACCESS static boost::python::list BuildMatrix(const std::array &m) { boost::python::list r_out; boost::python::list r[4]; @@ -97,12 +126,13 @@ static boost::python::list BuildMatrix(const std::array &m) { } static auto GetTransformMatrix(const carla::geom::Transform &self) { - return BuildMatrix(self.GetMatrix()); + return BuildMatrix(self.TransformationMatrix()); } static auto GetInverseTransformMatrix(const carla::geom::Transform &self) { - return BuildMatrix(self.GetInverseMatrix()); + return BuildMatrix(self.InverseTransformationMatrix()); } +#endif static auto Cross(const carla::geom::Vector3D &self, const carla::geom::Vector3D &other) { return carla::geom::Math::Cross(self, other); @@ -215,6 +245,42 @@ void export_geom() { .def(self_ns::str(self_ns::self)) ; + class_>("Acceleration") + .def(init((arg("x")=0.0f, arg("y")=0.0f, arg("z")=0.0f))) + .def(init((arg("rhs")))) + .add_property("x", +[](const cg::Acceleration &self) { return self.x; }, +[](cg::Acceleration &self, float x) { self.x = x; }) + .add_property("y", +[](const cg::Acceleration &self) { return self.y; }, +[](cg::Acceleration &self, float y) { self.y = y; }) + .add_property("z", +[](const cg::Acceleration &self) { return self.z; }, +[](cg::Acceleration &self, float z) { self.z = z; }) + .def("__eq__", &cg::Acceleration::operator==) + .def("__ne__", &cg::Acceleration::operator!=) + .def("__abs__", &cg::Acceleration::Abs) + .def(self_ns::str(self_ns::self)) + ; + + class_>("AngularVelocity") + .def(init((arg("x")=0.0f, arg("y")=0.0f, arg("z")=0.0f))) + .def(init((arg("rhs")))) + .add_property("x", +[](const cg::AngularVelocity &self) { return self.x; }, +[](cg::AngularVelocity &self, float x) { self.x = x; }) + .add_property("y", +[](const cg::AngularVelocity &self) { return self.y; }, +[](cg::AngularVelocity &self, float y) { self.y = y; }) + .add_property("z", +[](const cg::AngularVelocity &self) { return self.z; }, +[](cg::AngularVelocity &self, float z) { self.z = z; }) + .def("__eq__", &cg::AngularVelocity::operator==) + .def("__ne__", &cg::AngularVelocity::operator!=) + .def("__abs__", &cg::AngularVelocity::Abs) + .def(self_ns::str(self_ns::self)) + ; + + class_>("Velocity") + .def(init((arg("x")=0.0f, arg("y")=0.0f, arg("z")=0.0f))) + .def(init((arg("rhs")))) + .add_property("x", +[](const cg::Velocity &self) { return self.x; }, +[](cg::Velocity &self, float x) { self.x = x; }) + .add_property("y", +[](const cg::Velocity &self) { return self.y; }, +[](cg::Velocity &self, float y) { self.y = y; }) + .add_property("z", +[](const cg::Velocity &self) { return self.z; }, +[](cg::Velocity &self, float z) { self.z = z; }) + .def("__eq__", &cg::Velocity::operator==) + .def("__ne__", &cg::Velocity::operator!=) + .def("__abs__", &cg::Velocity::Abs) + .def(self_ns::str(self_ns::self)) + ; + class_("Rotation") .def(init((arg("pitch")=0.0f, arg("yaw")=0.0f, arg("roll")=0.0f))) .def_readwrite("pitch", &cg::Rotation::pitch) @@ -228,6 +294,37 @@ void export_geom() { .def(self_ns::str(self_ns::self)) ; + class_("Quaternion") + .def(init((arg("x")=0.0f, arg("y")=0.0f, arg("z")=0.0f, arg("w")=1.0f))) + .def(init((arg("rotator")))) + .def_readwrite("x", &cg::Quaternion::x) + .def_readwrite("y", &cg::Quaternion::y) + .def_readwrite("z", &cg::Quaternion::z) + .def_readwrite("w", &cg::Quaternion::w) + .def("create_from_yaw_degree", &cg::Quaternion::CreateFromYawDegree, (arg("yaw"))) + .def("identity", &cg::Quaternion::Identity) + .def("get_forward_vector", &cg::Quaternion::GetForwardVector) + .def("get_right_vector", &cg::Quaternion::GetRightVector) + .def("get_up_vector", &cg::Quaternion::GetUpVector) + .def("inverse", &cg::Quaternion::Inverse) + .def("length", &cg::Quaternion::Length) + .def("squared_length", &cg::Quaternion::SquaredLength) + .def("unit_quaternion", &cg::Quaternion::UnitQuaternion) +#if ALLOW_UNSAFE_GEOM_MATRIX_ACCESS + .def("rotation_matrix", &cg::Quaternion::RotationMatrix) + .def("inverse_rotation_matrix", &cg::Quaternion::InverseRotationMatrix) +#endif + .def("rotated_quaternion", &cg::Quaternion::RotatedQuaternion, (arg("quaternion"))) + .def("yaw_rad", &cg::Quaternion::YawRad) + .def("yaw_degree", &cg::Quaternion::YawDegree) + .def("rotator", &cg::Quaternion::Rotator) + .def("rotated_vector", &cg::Quaternion::RotatedVector, (arg("vector"))) + .def("inverse_rotated_vector", &cg::Quaternion::InverseRotatedVector, (arg("vector"))) + .def("__eq__", &cg::Quaternion::operator==) + .def("__ne__", &cg::Quaternion::operator!=) + .def(self_ns::str(self_ns::self)) + ; + class_("Transform") .def(init( (arg("location")=cg::Location(), arg("rotation")=cg::Rotation()))) @@ -249,8 +346,10 @@ void export_geom() { .def("get_forward_vector", &cg::Transform::GetForwardVector) .def("get_right_vector", &cg::Transform::GetRightVector) .def("get_up_vector", &cg::Transform::GetUpVector) +#if ALLOW_UNSAFE_GEOM_MATRIX_ACCESS .def("get_matrix", &GetTransformMatrix) .def("get_inverse_matrix", &GetInverseTransformMatrix) +#endif .def("__eq__", &cg::Transform::operator==) .def("__ne__", &cg::Transform::operator!=) .def(self_ns::str(self_ns::self)) diff --git a/PythonAPI/carla/source/libcarla/Sensor.cpp b/PythonAPI/carla/source/libcarla/Sensor.cpp index 481b12203bb..4010808d135 100644 --- a/PythonAPI/carla/source/libcarla/Sensor.cpp +++ b/PythonAPI/carla/source/libcarla/Sensor.cpp @@ -44,9 +44,6 @@ void export_sensor() { .def("listen_to_gbuffer", &SubscribeToGBuffer, (arg("gbuffer_id"), arg("callback"))) .def("is_listening_gbuffer", &cc::ServerSideSensor::IsListeningGBuffer, (arg("gbuffer_id"))) .def("stop_gbuffer", &cc::ServerSideSensor::StopGBuffer, (arg("gbuffer_id"))) - .def("enable_for_ros", &cc::ServerSideSensor::EnableForROS) - .def("disable_for_ros", &cc::ServerSideSensor::DisableForROS) - .def("is_enabled_for_ros", &cc::ServerSideSensor::IsEnabledForROS) .def("send", &cc::ServerSideSensor::Send, (arg("message"))) .def(self_ns::str(self_ns::self)) ; diff --git a/PythonAPI/carla/source/libcarla/V2XData.cpp b/PythonAPI/carla/source/libcarla/V2XData.cpp index 2be2198ce24..eabb43adf91 100644 --- a/PythonAPI/carla/source/libcarla/V2XData.cpp +++ b/PythonAPI/carla/source/libcarla/V2XData.cpp @@ -76,7 +76,7 @@ std::string GetSemiOrientationString(const long orientation) } } -std::string GetAltitudeConfidenceString(ITSContainer::AltitudeConfidence_t altitudeConfidence) +std::string GetAltitudeConfidenceString(const ITSContainer::AltitudeConfidence_t altitudeConfidence) { switch(altitudeConfidence) { @@ -114,7 +114,7 @@ std::string GetAltitudeConfidenceString(ITSContainer::AltitudeConfidence_t altit return "AltitudeConfidence_unavailable"; } } -static boost::python::dict GetReferenceContainer(const CAM_t message) +static boost::python::dict GetReferenceContainer(const CAM_t &message) { boost::python::dict ReferencePosition; ITSContainer::ReferencePosition_t ref = message.cam.camParameters.basicContainer.referencePosition; @@ -130,7 +130,7 @@ static boost::python::dict GetReferenceContainer(const CAM_t message) Altitude["Altitude Confidence"] = GetAltitudeConfidenceString(ref.altitude.altitudeConfidence); return ReferencePosition; } -static boost::python::dict GetBasicContainer(const CAM_t message) +static boost::python::dict GetBasicContainer(const CAM_t &message) { boost::python::dict BasicContainer; BasicContainer["Station Type"] = GetStationTypeString(message.cam.camParameters.basicContainer.stationType); @@ -138,7 +138,7 @@ static boost::python::dict GetBasicContainer(const CAM_t message) return BasicContainer; } -std::string GetHeadingConfidenceString(ITSContainer::HeadingConfidence_t confidence) +std::string GetHeadingConfidenceString(const ITSContainer::HeadingConfidence_t confidence) { switch (confidence) { @@ -153,7 +153,7 @@ std::string GetHeadingConfidenceString(ITSContainer::HeadingConfidence_t confide } } -std::string GetSpeedConfidenceString(ITSContainer::SpeedConfidence_t confidence) +std::string GetSpeedConfidenceString(const ITSContainer::SpeedConfidence_t confidence) { switch (confidence) { @@ -168,7 +168,7 @@ std::string GetSpeedConfidenceString(ITSContainer::SpeedConfidence_t confidence) } } -std::string GetVehicleLengthConfidenceString(ITSContainer::VehicleLengthConfidenceIndication_t confidence) +std::string GetVehicleLengthConfidenceString(const ITSContainer::VehicleLengthConfidenceIndication_t confidence) { switch (confidence) { @@ -185,7 +185,7 @@ std::string GetVehicleLengthConfidenceString(ITSContainer::VehicleLengthConfiden } } -std::string GetAccelerationConfidenceString(ITSContainer::AccelerationConfidence_t confidence) +std::string GetAccelerationConfidenceString(const ITSContainer::AccelerationConfidence_t confidence) { switch (confidence) { @@ -198,7 +198,7 @@ std::string GetAccelerationConfidenceString(ITSContainer::AccelerationConfidence } } -std::string GetCurvatureConfidenceString(ITSContainer::CurvatureConfidence_t confidence) +std::string GetCurvatureConfidenceString(const ITSContainer::CurvatureConfidence_t confidence) { switch (confidence) { @@ -221,7 +221,7 @@ std::string GetCurvatureConfidenceString(ITSContainer::CurvatureConfidence_t con } } -std::string GetYawRateConfidenceString(ITSContainer::YawRateConfidence_t confidence) +std::string GetYawRateConfidenceString(const ITSContainer::YawRateConfidence_t confidence) { switch (confidence) { @@ -246,7 +246,7 @@ std::string GetYawRateConfidenceString(ITSContainer::YawRateConfidence_t confide } } -std::string GetSteeringWheelConfidenceString(ITSContainer::SteeringWheelAngleConfidence_t confidence) +std::string GetSteeringWheelConfidenceString(const ITSContainer::SteeringWheelAngleConfidence_t confidence) { switch (confidence) { @@ -259,7 +259,7 @@ std::string GetSteeringWheelConfidenceString(ITSContainer::SteeringWheelAngleCon } } -static boost::python::dict GetBVCHighFrequency(const CAM_t message) +static boost::python::dict GetBVCHighFrequency(const CAM_t &message) { boost::python::dict BVCHighFrequency; CAMContainer::BasicVehicleContainerHighFrequency_t bvchf = message.cam.camParameters.highFrequencyContainer.basicVehicleContainerHighFrequency; @@ -380,12 +380,12 @@ static boost::python::dict GetBVCHighFrequency(const CAM_t message) return BVCHighFrequency; } -static boost::python::list GetProtectedCommunicationZone(const CAMContainer::RSUContainerHighFrequency_t rsuMessage) +static boost::python::list GetProtectedCommunicationZone(const CAMContainer::RSUContainerHighFrequency_t &rsuMessage) { boost::python::list PCZlist; - for (ITSContainer::ProtectedCommunicationZone_t data : rsuMessage.protectedCommunicationZonesRSU.list) - { + for (auto i=0u; i< rsuMessage.protectedCommunicationZonesRSU.ProtectedCommunicationZoneCount; ++i) { + ITSContainer::ProtectedCommunicationZone_t const &data=rsuMessage.protectedCommunicationZonesRSU.data[i]; boost::python::dict PCZDict; PCZDict["Protected Zone Type"] = data.protectedZoneType; if (data.expiryTimeAvailable) @@ -409,7 +409,7 @@ static boost::python::list GetProtectedCommunicationZone(const CAMContainer::RSU } return PCZlist; } -static boost::python::dict GetRSUHighFrequency(const CAM_t message) +static boost::python::dict GetRSUHighFrequency(const CAM_t &message) { boost::python::dict RSU; CAMContainer::RSUContainerHighFrequency_t rsu = message.cam.camParameters.highFrequencyContainer.rsuContainerHighFrequency; @@ -417,7 +417,7 @@ static boost::python::dict GetRSUHighFrequency(const CAM_t message) return RSU; } -static boost::python::dict GetHighFrequencyContainer(const CAM_t message) +static boost::python::dict GetHighFrequencyContainer(const CAM_t &message) { boost::python::dict HFC; CAMContainer::HighFrequencyContainer_t hfc = message.cam.camParameters.highFrequencyContainer; @@ -436,7 +436,8 @@ static boost::python::dict GetHighFrequencyContainer(const CAM_t message) } return HFC; } -std::string GetVehicleRoleString(ITSContainer::VehicleRole_t vehicleRole) + +std::string GetVehicleRoleString(const ITSContainer::VehicleRole_t &vehicleRole) { switch (vehicleRole) { @@ -475,12 +476,14 @@ std::string GetVehicleRoleString(ITSContainer::VehicleRole_t vehicleRole) } } -boost::python::list GetPathHistory(const ITSContainer::PathHistory_t pathHistory) +boost::python::list GetPathHistory(const ITSContainer::PathHistory_t &pathHistory) { boost::python::list PathHistoryList; - for (ITSContainer::PathPoint_t pathPoint : pathHistory.data) + + for (auto i=0u; i. #include +#include #include #include #include @@ -172,6 +173,7 @@ static std::string ExportCosmosRoadMarkings( void export_world() { using namespace boost::python; + namespace ca = carla::actors; namespace cc = carla::client; namespace cg = carla::geom; namespace cr = carla::rpc; @@ -340,7 +342,7 @@ void export_world() { #define SPAWN_ACTOR_WITHOUT_GIL(fn) +[]( \ cc::World &self, \ - const cc::ActorBlueprint &blueprint, \ + const ca::ActorBlueprint &blueprint, \ const cg::Transform &transform, \ cc::Actor *parent, \ cr::AttachmentType attachment_type, \ diff --git a/PythonAPI/examples/generate_traffic.py b/PythonAPI/examples/generate_traffic.py index 9158583003b..3acbc14189f 100755 --- a/PythonAPI/examples/generate_traffic.py +++ b/PythonAPI/examples/generate_traffic.py @@ -148,9 +148,9 @@ def main(): all_id = [] client = carla.Client(args.host, args.port) client.set_timeout(10.0) - synchronous_master = False random.seed(args.seed if args.seed is not None else int(time.time())) + original_world_settings = None try: world = client.get_world() @@ -164,15 +164,14 @@ def main(): if args.seed is not None: traffic_manager.set_random_device_seed(args.seed) - settings = world.get_settings() + original_world_settings = world.get_settings() + print("current_world_settings {}".format(original_world_settings)) + settings = original_world_settings if not args.asynch: traffic_manager.set_synchronous_mode(True) if not settings.synchronous_mode: - synchronous_master = True settings.synchronous_mode = True settings.fixed_delta_seconds = 0.05 - else: - synchronous_master = False else: print("You are currently in asynchronous mode. If this is a traffic simulation, \ you could experience some issues. If it's not working correctly, switch to synchronous \ @@ -180,7 +179,9 @@ def main(): if args.no_rendering: settings.no_rendering_mode = True + print("apply_world_settings {}".format(settings)) world.apply_settings(settings) + print("settings applied") blueprints = get_actor_blueprints(world, args.filterv, args.generationv) if not blueprints: @@ -229,7 +230,7 @@ def main(): batch.append(SpawnActor(blueprint, transform) .then(SetAutopilot(FutureActor, True, traffic_manager.get_port()))) - for response in client.apply_batch_sync(batch, synchronous_master): + for response in client.apply_batch_sync(batch, do_tick=True): if response.error: logging.error(response.error) else: @@ -281,7 +282,7 @@ def main(): print("Walker has no speed") walker_speed.append(0.0) batch.append(SpawnActor(walker_bp, spawn_point)) - results = client.apply_batch_sync(batch, True) + results = client.apply_batch_sync(batch, do_tick=True) walker_speed2 = [] for i in range(len(results)): if results[i].error: @@ -295,7 +296,7 @@ def main(): walker_controller_bp = world.get_blueprint_library().find('controller.ai.walker') for i in range(len(walkers_list)): batch.append(SpawnActor(walker_controller_bp, carla.Transform(), walkers_list[i]["id"])) - results = client.apply_batch_sync(batch, True) + results = client.apply_batch_sync(batch, do_tick=True) for i in range(len(results)): if results[i].error: logging.error(results[i].error) @@ -308,7 +309,7 @@ def main(): all_actors = world.get_actors(all_id) # wait for a tick to ensure client receives the last transform of the walkers we have just created - if args.asynch or not synchronous_master: + if args.asynch: world.wait_for_tick() else: world.tick() @@ -330,18 +331,22 @@ def main(): traffic_manager.global_percentage_speed_difference(30.0) while True: - if not args.asynch and synchronous_master: + if not args.asynch: world.tick() else: world.wait_for_tick() finally: - if not args.asynch and synchronous_master: - settings = world.get_settings() - settings.synchronous_mode = False - settings.no_rendering_mode = False - settings.fixed_delta_seconds = None + if not args.asynch: + if original_world_settings: + settings= original_world_settings + else: + settings = world.get_settings() + settings.synchronous_mode = False + settings.no_rendering_mode = False + settings.fixed_delta_seconds = None + print("restore world_settings {}".format(settings)) world.apply_settings(settings) print('\ndestroying %d vehicles' % len(vehicles_list)) diff --git a/PythonAPI/test/unit/test_transform.py b/PythonAPI/test/unit/test_transform.py index 86dfc77bc95..5a9681dbe6b 100644 --- a/PythonAPI/test/unit/test_transform.py +++ b/PythonAPI/test/unit/test_transform.py @@ -147,7 +147,8 @@ def test_rotation_and_translation(self): point = carla.Location(x=0.0, y=0.0, z=2.0) t.transform(point) - self.assertTrue(abs(point.x - (-2.0)) <= error) + #!!! This solution_list was wrong in CARLA version <= 0.9.16 due to invalid pitch AND roll rotations, (most relevant) yaw rotations were not affected + self.assertTrue(abs(point.x - (2.0)) <= error) self.assertTrue(abs(point.y - 0.0) <= error) self.assertTrue(abs(point.z - (-1.0)) <= error) @@ -163,9 +164,10 @@ def test_list_rotation_and_translation_location(self): ] t.transform(point_list) - solution_list = [carla.Location(-2.0, 0.0, -1.0), - carla.Location(-1.0, 10.0, -1.0), - carla.Location(-2.0, 18.0, -1.0) + #!!! This solution_list was wrong in CARLA version <= 0.9.16 due to invalid pitch AND roll rotations, (most relevant) yaw rotations were not affected + solution_list = [carla.Location(2.0, 0.0, -1.0), + carla.Location(1.0, 10.0, -1.0), + carla.Location(2.0, 18.0, -1.0) ] for i in range(len(point_list)): @@ -185,9 +187,10 @@ def test_list_rotation_and_translation_vector3d(self): ] t.transform(point_list) - solution_list = [carla.Vector3D(-2.0, 0.0, -1.0), - carla.Vector3D(-1.0, 10.0, -1.0), - carla.Vector3D(-2.0, 18.0, -1.0) + #!!! This solution_list was wrong in CARLA version <= 0.9.15 due to invalid pitch AND roll rotations, (most relevant) yaw rotations were not affected + solution_list = [carla.Vector3D(2.0, 0.0, -1.0), + carla.Vector3D(1.0, 10.0, -1.0), + carla.Vector3D(2.0, 18.0, -1.0) ] for i in range(len(point_list)): diff --git a/Unreal/CarlaUE4/Config/DefaultGame.ini b/Unreal/CarlaUE4/Config/DefaultGame.ini index 228cab74957..9efcd588c50 100644 --- a/Unreal/CarlaUE4/Config/DefaultGame.ini +++ b/Unreal/CarlaUE4/Config/DefaultGame.ini @@ -17,6 +17,8 @@ LowRoadPieceMeshMaxDrawDistance=15000.000000 +EpicRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/WetPavement/WetPavement_Complex_Concrete.WetPavement_Complex_Concrete"',MaterialSlotName="TileRoad_Curb",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) +EpicRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/Ground/SideWalks/SidewalkN4/WetPavement_SidewalkN4.WetPavement_SidewalkN4"',MaterialSlotName="Tileroad_Sidewalk",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) +EpicRoadMaterials=(MaterialInterface=MaterialInstanceConstant'"/Game/Carla/Static/GenericMaterials/LaneMarking/Lanemarking.Lanemarking"',MaterialSlotName="TileRoad_LaneMarkingSolid",ImportedMaterialSlotName="",UVChannelData=(bInitialized=False,bOverrideDensities=False,LocalUVDensities[0]=0.000000,LocalUVDensities[1]=0.000000,LocalUVDensities[2]=0.000000,LocalUVDensities[3]=0.000000)) +ROS2=True +ROS2TopicVisibility=True [/Script/UnrealEd.ProjectPackagingSettings] Build=IfProjectHasCode @@ -72,3 +74,4 @@ bSkipEditorContent=False +DirectoriesToAlwaysStageAsUFS=(Path="Carla/Config") bNativizeBlueprintAssets=False bNativizeOnlySelectedBlueprints=False + diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp index ab55b30ef00..177da2fa10d 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp @@ -1126,6 +1126,13 @@ void UActorBlueprintFunctionLibrary::MakeV2XDefinition( FillIdAndTags(Definition, TEXT("sensor"), TEXT("other"), TEXT("v2x")); AddVariationsForSensor(Definition); + // - Channel id -------------------------------- + FActorVariation ChannelId; + ChannelId.Id = TEXT("channel_id"); + ChannelId.Type = EActorAttributeType::String; + ChannelId.RecommendedValues = { TEXT("Default") }; + ChannelId.bRestrictToRecommended = false; + // - Noise seed -------------------------------- FActorVariation NoiseSeed; NoiseSeed.Id = TEXT("noise_seed"); @@ -1311,6 +1318,7 @@ void UActorBlueprintFunctionLibrary::MakeV2XDefinition( StdDevVelX.bRestrictToRecommended = false; Definition.Variations.Append({ + ChannelId, NoiseSeed, TransmitPower, ReceiverSensitivity, @@ -1359,6 +1367,13 @@ void UActorBlueprintFunctionLibrary::MakeCustomV2XDefinition( FillIdAndTags(Definition, TEXT("sensor"), TEXT("other"), TEXT("v2x_custom")); AddVariationsForSensor(Definition); + // - Channel id -------------------------------- + FActorVariation ChannelId; + ChannelId.Id = TEXT("channel_id"); + ChannelId.Type = EActorAttributeType::String; + ChannelId.RecommendedValues = { TEXT("Default") }; + ChannelId.bRestrictToRecommended = false; + // - Noise seed -------------------------------- FActorVariation NoiseSeed; NoiseSeed.Id = TEXT("noise_seed"); @@ -1437,6 +1452,7 @@ void UActorBlueprintFunctionLibrary::MakeCustomV2XDefinition( Definition.Variations.Append({ + ChannelId, NoiseSeed, TransmitPower, ReceiverSensitivity, diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp index 2cc4821ea01..d8053e710e3 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp @@ -8,17 +8,44 @@ #include "Carla/Actor/ActorDispatcher.h" #include "Carla/Actor/ActorBlueprintFunctionLibrary.h" -#include "Carla/Actor/ActorROS2Handler.h" #include "Carla/Actor/CarlaActorFactory.h" +#include "Carla/Util/BoundingBoxCalculator.h" #include "Carla/Game/Tagger.h" #include "Carla/Vehicle/VehicleControl.h" #include "GameFramework/Controller.h" -#include -#include "carla/ros2/ROS2.h" -#include +#if defined(WITH_ROS2) +# include +# include "carla/ros2/ROS2.h" +# include "carla/ros2/types/PublisherSensorType.h" +# include "carla/ros2/types/SensorActorDefinition.h" +# include "carla/ros2/types/VehicleActorDefinition.h" +# include "carla/ros2/types/WalkerActorDefinition.h" +# include "carla/ros2/types/TrafficSignActorDefinition.h" +# include "carla/ros2/types/TrafficLightActorDefinition.h" +# include + +# include "Carla/Sensor/CollisionSensor.h" +# include "Carla/Sensor/CustomV2XSensor.h" +# include "Carla/Sensor/DepthCamera.h" +# include "Carla/Sensor/NormalsCamera.h" +# include "Carla/Sensor/DVSCamera.h" +# include "Carla/Sensor/GnssSensor.h" +# include "Carla/Sensor/InertialMeasurementUnit.h" +# include "Carla/Sensor/LaneInvasionSensor.h" +# include "Carla/Sensor/ObstacleDetectionSensor.h" +# include "Carla/Sensor/OpticalFlowCamera.h" +# include "Carla/Sensor/Radar.h" +# include "Carla/Sensor/RayCastLidar.h" +# include "Carla/Sensor/RayCastSemanticLidar.h" +# include "Carla/Sensor/RssSensor.h" +# include "Carla/Sensor/SceneCaptureCamera.h" +# include "Carla/Sensor/SemanticSegmentationCamera.h" +# include "Carla/Sensor/InstanceSegmentationCamera.h" +# include "Carla/Sensor/V2XSensor.h" +#endif void UActorDispatcher::Bind(FActorDefinition Definition, SpawnFunctionType Functor) { @@ -172,6 +199,142 @@ bool UActorDispatcher::DestroyActor(FCarlaActor::IdType ActorId) return true; } +#if defined(WITH_ROS2) +carla::ros2::types::PublisherSensorType GetPublisherSensorType(ASensor * Sensor) { + // map the Ue4 sensors to their ESensor type and stream_id + carla::ros2::types::PublisherSensorType SensorType = carla::ros2::types::PublisherSensorType::Unknown; + if ( dynamic_cast(Sensor) ) { + SensorType = carla::ros2::types::PublisherSensorType::CollisionSensor; + } else if ( dynamic_cast(Sensor) ) { + SensorType = carla::ros2::types::PublisherSensorType::DepthCamera; + } else if ( dynamic_cast(Sensor) ) { + SensorType = carla::ros2::types::PublisherSensorType::NormalsCamera; + } else if ( dynamic_cast(Sensor) ) { + SensorType = carla::ros2::types::PublisherSensorType::DVSCamera; + } else if ( dynamic_cast(Sensor) ) { + SensorType = carla::ros2::types::PublisherSensorType::GnssSensor; + } else if ( dynamic_cast(Sensor) ) { + SensorType = carla::ros2::types::PublisherSensorType::InertialMeasurementUnit; + } else if ( dynamic_cast(Sensor) ) { + SensorType = carla::ros2::types::PublisherSensorType::LaneInvasionSensor; + } else if ( dynamic_cast(Sensor) ) { + SensorType = carla::ros2::types::PublisherSensorType::ObstacleDetectionSensor; + } else if ( dynamic_cast(Sensor) ) { + SensorType = carla::ros2::types::PublisherSensorType::OpticalFlowCamera; + } else if ( dynamic_cast(Sensor) ) { + SensorType = carla::ros2::types::PublisherSensorType::Radar; + // BE CAREFUL: FIRST CHECK ARayCastLidar, because that's derived from RayCastSemanticLidar!! + } else if ( dynamic_cast(Sensor) ) { + SensorType = carla::ros2::types::PublisherSensorType::RayCastLidar; + } else if ( dynamic_cast(Sensor) ) { + SensorType = carla::ros2::types::PublisherSensorType::RayCastSemanticLidar; + } else if ( dynamic_cast(Sensor) ) { + SensorType = carla::ros2::types::PublisherSensorType::RssSensor; + } else if ( dynamic_cast(Sensor) ) { + SensorType = carla::ros2::types::PublisherSensorType::SceneCaptureCamera; + } else if ( dynamic_cast(Sensor) ) { + SensorType = carla::ros2::types::PublisherSensorType::SemanticSegmentationCamera; + } else if ( dynamic_cast(Sensor) ) { + SensorType = carla::ros2::types::PublisherSensorType::InstanceSegmentationCamera; + } else if ( dynamic_cast(Sensor) ) { + SensorType = carla::ros2::types::PublisherSensorType::CameraGBufferUint8; + } else if ( dynamic_cast(Sensor) ) { + SensorType = carla::ros2::types::PublisherSensorType::CameraGBufferFloat; + } else if ( dynamic_cast(Sensor) ) { + SensorType = carla::ros2::types::PublisherSensorType::V2XCustom; + } else if ( dynamic_cast(Sensor) ) { + SensorType = carla::ros2::types::PublisherSensorType::V2X; + } else { + // not derived from ASensor, is initialized in each case separately + //carla::ros2::types::PublisherSensorType::WorldObserver + + carla::log_error("Getcarla::ros2::types::PublisherSensorType : invalid sensor type"); + } + return SensorType; +} + +void RegisterActorROS2(std::shared_ptr ROS2, FCarlaActor* CarlaActor, carla::ros2::types::ActorNameDefinition ActorNameDefinition) { + auto *Sensor = Cast(CarlaActor->GetActor()); + auto *Vehicle = Cast(CarlaActor->GetActor()); + auto *Walker = Cast(CarlaActor->GetActor()); + auto *TrafficLight = Cast(CarlaActor->GetActor()); + auto *TrafficSign = Cast(CarlaActor->GetActor()); + if ( Sensor != nullptr ) { + auto SensorActorDefinition = std::make_shared( + ActorNameDefinition, + GetPublisherSensorType(Sensor), + carla::streaming::detail::token_type(Sensor->GetToken()).get_stream_id()); + auto *V2XCustomSensor = Cast(CarlaActor->GetActor()); + if (V2XCustomSensor != nullptr) { + carla::ros2::types::V2XCustomSendCallback V2XCustomSendCallback = [V2XCustomSensor](carla::rpc::CustomV2XBytes const &Data) -> void { + V2XCustomSensor->Send(Data); + }; + ROS2->AddV2XCustomSensorUe(SensorActorDefinition, V2XCustomSendCallback); + } + else { + ROS2->AddSensorUe(SensorActorDefinition); + } + } + else if (Vehicle != nullptr ) { + FVehiclePhysicsControl PhysicsControl; + CarlaActor->GetPhysicsControl(PhysicsControl); + + auto VehicleActorDefinition = std::make_shared( + carla::ros2::types::ActorDefinition(ActorNameDefinition, + CarlaActor->GetActorInfo()->BoundingBox, + carla::ros2::types::Polygon()), + PhysicsControl); + auto SkeletalMeshComponent = Vehicle->GetMesh(); + if (SkeletalMeshComponent != nullptr) { + VehicleActorDefinition->vertex_polygon.SetGlobalVertices(UBoundingBoxCalculator::GetSkeletalMeshVertices(SkeletalMeshComponent->SkeletalMesh)); + } + + carla::ros2::types::VehicleControlCallback VehicleControlCallback = [Vehicle](carla::ros2::types::VehicleControl const &Source) -> void { + EVehicleInputPriority InputPriority = EVehicleInputPriority(Source.ControlPriority()); + if ( InputPriority <= EVehicleInputPriority::User) { + // priority at least on User level, but allow multiple input prios to allow e.g. manual overrides + InputPriority = EVehicleInputPriority::User; + } + Vehicle->ApplyVehicleControl(Source.GetVehicleControl(), InputPriority); + }; + + carla::ros2::types::VehicleAckermannControlCallback VehicleAckermannControlCallback = [Vehicle](carla::ros2::types::VehicleAckermannControl const &Source) -> void { + Vehicle->ApplyVehicleAckermannControl(Source.GetVehicleAckermannControl(), EVehicleInputPriority::User); + }; + carla::ros2::types::ActorSetTransformCallback VehicleSetTransformCallback = [Vehicle](carla::ros2::types::Transform const &Transform) -> void { + Vehicle->SetActorTransform(Transform.GetTransform()); + }; + + ROS2->AddVehicleUe(VehicleActorDefinition, VehicleControlCallback, VehicleAckermannControlCallback, VehicleSetTransformCallback); + } + else if ( Walker != nullptr ) { + auto WalkerActorDefinition = std::make_shared( + carla::ros2::types::ActorDefinition(ActorNameDefinition, + CarlaActor->GetActorInfo()->BoundingBox, + carla::ros2::types::Polygon())); + auto SkeletalMeshComponent = Walker->GetMesh(); + if (SkeletalMeshComponent != nullptr) { + WalkerActorDefinition->vertex_polygon.SetGlobalVertices(UBoundingBoxCalculator::GetSkeletalMeshVertices(SkeletalMeshComponent->SkeletalMesh)); + } + + auto WalkerController = Cast(Walker->GetController()); + carla::ros2::types::WalkerControlCallback walker_control_callback = [WalkerController](carla::ros2::types::WalkerControl const &Source) -> void { + WalkerController->ApplyWalkerControl(Source.GetWalkerControl()); + }; + + ROS2->AddWalkerUe(WalkerActorDefinition, walker_control_callback); + } + else if ( TrafficLight != nullptr ) { + auto TrafficLightActorDefinition = std::make_shared(ActorNameDefinition); + ROS2->AddTrafficLightUe(TrafficLightActorDefinition); + } + else if ( TrafficSign != nullptr ) { + auto TrafficSignActorDefinition = std::make_shared(ActorNameDefinition); + ROS2->AddTrafficSignUe(TrafficSignActorDefinition); + } +} +#endif + FCarlaActor* UActorDispatcher::RegisterActor( AActor &Actor, FActorDescription Description, FActorRegistry::IdType DesiredId) @@ -186,40 +349,23 @@ FCarlaActor* UActorDispatcher::RegisterActor( auto ROS2 = carla::ros2::ROS2::GetInstance(); if (ROS2->IsEnabled()) { - std::string RosName = std::string(TCHAR_TO_UTF8(*Description.GetAttribute("ros_name").Value)); - // If not specified by the user, set the ActorId as the actor name - if (RosName.empty()) - { - RosName = "actor" + std::to_string(View->GetActorId()); + bool EnabledForRos = false; + if ( (Description.GetAttribute("enabled_for_ros").Value.Equals(TEXT(""))) && (ROS2->VisibilityDefaultMode() == carla::ros2::ROS2::TopicVisibilityDefaultMode::eOn )) { + EnabledForRos = true; } - - std::string FrameId = std::string(TCHAR_TO_UTF8(*Description.GetAttribute("ros_frame_id").Value)); - // If not specified by the user, set the actor name as the frame id - if (FrameId.empty()) - { - FrameId = RosName; + else { + EnabledForRos = Description.GetAttribute("enabled_for_ros").Value.ToBool(); } - bool PublishTF = UActorBlueprintFunctionLibrary::RetrieveActorAttributeToBool( - "ros_publish_tf", - Description.Variations, - true); - - auto *Sensor = Cast(View->GetActor()); - auto *Vehicle = Cast(View->GetActor()); - if (Sensor != nullptr) - { - ROS2->RegisterSensor(static_cast(&Actor), RosName, FrameId, PublishTF); - } - else if (Vehicle != nullptr && Description.GetAttribute("role_name").Value == "hero") - { - ROS2->RegisterVehicle(static_cast(&Actor), RosName, RosName, [RosName](void *Actor, carla::ros2::ROS2CallbackData Data) -> void - { - AActor *UEActor = reinterpret_cast(Actor); - ActorROS2Handler Handler(UEActor, RosName); - boost::variant2::visit(Handler, Data); - }); - } + carla::ros2::types::ActorNameDefinition ActorNameDefinition( + View->GetActorId(), + std::string(TCHAR_TO_UTF8(*View->GetActorInfo()->Description.Id)), + std::string(TCHAR_TO_UTF8(*Description.GetAttribute("ros_name").Value)), + std::string(TCHAR_TO_UTF8(*Description.GetAttribute("role_name").Value)), + std::string(TCHAR_TO_UTF8(*Description.GetAttribute("object_type").Value)), + std::string(TCHAR_TO_UTF8(*Description.GetAttribute("base_type").Value)), + EnabledForRos); + RegisterActorROS2(ROS2, View, ActorNameDefinition); } #endif } @@ -241,27 +387,20 @@ void UActorDispatcher::OnActorDestroyed(AActor *Actor) FCarlaActor* CarlaActor = Registry.FindCarlaActor(Actor); if (CarlaActor) { + auto const ActorId = CarlaActor->GetActorId(); + #if defined(WITH_ROS2) auto ROS2 = carla::ros2::ROS2::GetInstance(); if (ROS2->IsEnabled()) { - auto Description = CarlaActor->GetActorInfo()->Description; - - auto *Sensor = Cast(Actor); - auto *Vehicle = Cast(Actor); - if (Sensor != nullptr) - { - ROS2->UnregisterSensor(static_cast(Actor)); - } - else if (Vehicle != nullptr && Description.GetAttribute("role_name").Value == "hero") { - ROS2->UnregisterVehicle(static_cast(Actor)); - } + ROS2->RemoveActor(ActorId); } #endif if (CarlaActor->IsActive()) { - Registry.Deregister(CarlaActor->GetActorId()); + Registry.Deregister(ActorId); } } + } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorROS2Handler.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorROS2Handler.cpp deleted file mode 100644 index 9e51503dafb..00000000000 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorROS2Handler.cpp +++ /dev/null @@ -1,49 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include "ActorROS2Handler.h" - -#include "Carla/Vehicle/CarlaWheeledVehicle.h" -#include "Carla/Vehicle/VehicleControl.h" -#include "Carla/Vehicle/VehicleAckermannControl.h" - -void ActorROS2Handler::operator()(carla::ros2::VehicleControl &Source) -{ - if (!_Actor) return; - - ACarlaWheeledVehicle *Vehicle = Cast(_Actor); - if (!Vehicle) return; - - // setup control values - FVehicleControl NewControl; - NewControl.Throttle = Source.throttle; - NewControl.Steer = Source.steer; - NewControl.Brake = Source.brake; - NewControl.bHandBrake = Source.hand_brake; - NewControl.bReverse = Source.reverse; - NewControl.bManualGearShift = Source.manual_gear_shift; - NewControl.Gear = Source.gear; - - Vehicle->ApplyVehicleControl(NewControl, EVehicleInputPriority::User); -} - -void ActorROS2Handler::operator()(carla::ros2::AckermannControl &Source) -{ - if (!_Actor) return; - - ACarlaWheeledVehicle *Vehicle = Cast(_Actor); - if (!Vehicle) return; - - // setup control values - FVehicleAckermannControl NewControl; - NewControl.Steer = Source.steer; - NewControl.SteerSpeed = Source.steer_speed; - NewControl.Speed = Source.speed; - NewControl.Acceleration = Source.acceleration; - NewControl.Jerk = Source.jerk; - - Vehicle->ApplyVehicleAckermannControl(NewControl, EVehicleInputPriority::User); -} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorROS2Handler.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorROS2Handler.h deleted file mode 100644 index dafe5876fcc..00000000000 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorROS2Handler.h +++ /dev/null @@ -1,26 +0,0 @@ -// Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include -#include "carla/ros2/ROS2.h" -#include - -/// visitor class -class ActorROS2Handler -{ - public: - ActorROS2Handler() = delete; - ActorROS2Handler(AActor *Actor, std::string RosName) : _Actor(Actor), _RosName(RosName) {}; - - void operator()(carla::ros2::VehicleControl &Source); - void operator()(carla::ros2::AckermannControl &Source); - - private: - AActor *_Actor {nullptr}; - std::string _RosName; -}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.cpp index 3e2f5e87116..4c463beae4e 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.cpp @@ -23,7 +23,7 @@ namespace crp = carla::rpc; FActorRegistry::IdType FActorRegistry::ID_COUNTER = 0u; -static FCarlaActor::ActorType FActorRegistry_GetActorType(const AActor *Actor) +FCarlaActor::ActorType FActorRegistry::GetActorType(const AActor *Actor) { if (!Actor) { @@ -34,7 +34,7 @@ static FCarlaActor::ActorType FActorRegistry_GetActorType(const AActor *Actor) { return FCarlaActor::ActorType::Vehicle; } - else if (nullptr != Cast(Actor)) + else if (nullptr != Cast(Actor)) { return FCarlaActor::ActorType::Walker; } @@ -174,7 +174,7 @@ TSharedPtr FActorRegistry::MakeCarlaActor( std::begin(Token.data), std::end(Token.data)); } - auto Type = FActorRegistry_GetActorType(&Actor); + auto Type = GetActorType(&Actor); TSharedPtr CarlaActor = FCarlaActor::ConstructCarlaActor( Id, &Actor, @@ -237,7 +237,7 @@ void FActorRegistry::WakeActorUp(FCarlaActor::IdType Id, UCarlaEpisode* CarlaEpi } } -FString FActorRegistry::GetDescriptionFromStream(carla::streaming::detail::stream_id_type Id) +FCarlaActor* FActorRegistry::FindCarlaActorByStreamId(carla::streaming::detail::stream_id_type Id) const { for (auto &Item : ActorDatabase) { @@ -248,9 +248,8 @@ FString FActorRegistry::GetDescriptionFromStream(carla::streaming::detail::strea carla::streaming::detail::token_type token(Sensor->GetToken()); if (token.get_stream_id() == Id) { - const FActorInfo *Info = Item.Value->GetActorInfo(); - return Info->Description.Id; + return Item.Value.Get(); } } - return FString(""); + return nullptr; } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.h index 285a446c1fd..24f1321c957 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorRegistry.h @@ -90,12 +90,15 @@ class FActorRegistry return PtrToId ? FindCarlaActor(*PtrToId) : nullptr; } - FString GetDescriptionFromStream(carla::streaming::detail::stream_id_type Id); + FCarlaActor* FindCarlaActorByStreamId(carla::streaming::detail::stream_id_type Id) const; void PutActorToSleep(IdType Id, UCarlaEpisode* CarlaEpisode); void WakeActorUp(IdType Id, UCarlaEpisode* CarlaEpisode); + static FCarlaActor::ActorType GetActorType(const AActor *Actor); + + /// @} // =========================================================================== /// @name Range iteration support diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.cpp index 44e27c83d7e..3ed1bdd67df 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.cpp @@ -73,6 +73,10 @@ FSensorActor::FSensorActor( Type = ActorType::Sensor; ActorData = MakeShared(); } + +ASensor* FSensorActor::GetSensor() { return dynamic_cast(GetActor()); } + + FTrafficSignActor::FTrafficSignActor( IdType ActorId, AActor* Actor, diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.h index c0b7fcf3e85..1f48dc26c5e 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/CarlaActor.h @@ -19,6 +19,7 @@ #include "Carla/Server/CarlaServerResponse.h" class AActor; +class ASensor; /// A view over an actor and its properties. class FCarlaActor @@ -176,6 +177,8 @@ class FCarlaActor return dynamic_cast(ActorData.Get()); } + FActorAttribute GetAttribute(const FString Name) const { return Info->Description.GetAttribute(Name); } + // Actor function interface ---------------------- // General functions @@ -499,28 +502,28 @@ class FVehicleActor : public FCarlaActor carla::rpc::ActorState InState, UWorld* World); - virtual ECarlaServerResponse EnableActorConstantVelocity(const FVector& Velocity) final; + ECarlaServerResponse EnableActorConstantVelocity(const FVector& Velocity) override final; - virtual ECarlaServerResponse DisableActorConstantVelocity() final; + ECarlaServerResponse DisableActorConstantVelocity() override final; - virtual ECarlaServerResponse GetPhysicsControl(FVehiclePhysicsControl& PhysicsControl) final; + ECarlaServerResponse GetPhysicsControl(FVehiclePhysicsControl& PhysicsControl) override final; - virtual ECarlaServerResponse GetFailureState(carla::rpc::VehicleFailureState&) final; + ECarlaServerResponse GetFailureState(carla::rpc::VehicleFailureState&) override final; - virtual ECarlaServerResponse GetVehicleLightState(FVehicleLightState& LightState) final; + ECarlaServerResponse GetVehicleLightState(FVehicleLightState& LightState) override final; - virtual ECarlaServerResponse OpenVehicleDoor(const EVehicleDoor DoorIdx) final; + ECarlaServerResponse OpenVehicleDoor(const EVehicleDoor DoorIdx) override final; - virtual ECarlaServerResponse CloseVehicleDoor(const EVehicleDoor DoorIdx) final; + ECarlaServerResponse CloseVehicleDoor(const EVehicleDoor DoorIdx) override final; - virtual ECarlaServerResponse ApplyPhysicsControl( - const FVehiclePhysicsControl& PhysicsControl) final; + ECarlaServerResponse ApplyPhysicsControl( + const FVehiclePhysicsControl& PhysicsControl) override final; - virtual ECarlaServerResponse SetVehicleLightState( - const FVehicleLightState& LightState) final; + ECarlaServerResponse SetVehicleLightState( + const FVehicleLightState& LightState) override final; - virtual ECarlaServerResponse SetWheelSteerDirection( - const EVehicleWheelLocation& WheelLocation, float AngleInDeg) final; + ECarlaServerResponse SetWheelSteerDirection( + const EVehicleWheelLocation& WheelLocation, float AngleInDeg) override final; virtual ECarlaServerResponse GetWheelSteerAngle( const EVehicleWheelLocation& WheelLocation, float& Angle) final; @@ -531,38 +534,38 @@ class FVehicleActor : public FCarlaActor virtual ECarlaServerResponse GetWheelPitchAngle( const EVehicleWheelLocation& WheelLocation, float& Angle) final; - virtual ECarlaServerResponse SetActorSimulatePhysics(bool bSimulatePhysics) final; + ECarlaServerResponse SetActorSimulatePhysics(bool bSimulatePhysics) override final; - virtual ECarlaServerResponse ApplyControlToVehicle( - const FVehicleControl&, const EVehicleInputPriority&) final; + ECarlaServerResponse ApplyControlToVehicle( + const FVehicleControl&, const EVehicleInputPriority&) override final; - virtual ECarlaServerResponse ApplyAckermannControlToVehicle( - const FVehicleAckermannControl&, const EVehicleInputPriority&) final; + ECarlaServerResponse ApplyAckermannControlToVehicle( + const FVehicleAckermannControl&, const EVehicleInputPriority&) override final; - virtual ECarlaServerResponse GetVehicleControl(FVehicleControl&) final; + ECarlaServerResponse GetVehicleControl(FVehicleControl&) override final; - virtual ECarlaServerResponse GetVehicleAckermannControl(FVehicleAckermannControl&) final; + ECarlaServerResponse GetVehicleAckermannControl(FVehicleAckermannControl&) override final; - virtual ECarlaServerResponse GetAckermannControllerSettings(FAckermannControllerSettings&) final; + ECarlaServerResponse GetAckermannControllerSettings(FAckermannControllerSettings&) override final; - virtual ECarlaServerResponse ApplyAckermannControllerSettings(const FAckermannControllerSettings&) final; + ECarlaServerResponse ApplyAckermannControllerSettings(const FAckermannControllerSettings&) override final; - virtual ECarlaServerResponse SetActorAutopilot(bool bEnabled, bool bKeepState = false) final; + ECarlaServerResponse SetActorAutopilot(bool bEnabled, bool bKeepState = false) override final; - virtual ECarlaServerResponse GetVehicleTelemetryData(FVehicleTelemetryData&) final; + ECarlaServerResponse GetVehicleTelemetryData(FVehicleTelemetryData&) override final; - virtual ECarlaServerResponse ShowVehicleDebugTelemetry(bool bEnabled) final; + ECarlaServerResponse ShowVehicleDebugTelemetry(bool bEnabled) override final; - virtual ECarlaServerResponse EnableCarSim(const FString& SimfilePath) final; + ECarlaServerResponse EnableCarSim(const FString& SimfilePath) override final; - virtual ECarlaServerResponse UseCarSimRoad(bool bEnabled) final; + ECarlaServerResponse UseCarSimRoad(bool bEnabled) override final; - virtual ECarlaServerResponse EnableChronoPhysics( + ECarlaServerResponse EnableChronoPhysics( uint64_t MaxSubsteps, float MaxSubstepDeltaTime, const FString& VehicleJSON, const FString& PowertrainJSON, - const FString& TireJSON, const FString& BaseJSONPath) final; + const FString& TireJSON, const FString& BaseJSONPath) override final; - virtual ECarlaServerResponse RestorePhysXPhysics(); + ECarlaServerResponse RestorePhysXPhysics() override final; }; class FSensorActor : public FCarlaActor @@ -575,6 +578,7 @@ class FSensorActor : public FCarlaActor carla::rpc::ActorState InState, UWorld* World); + ASensor* GetSensor(); }; class FTrafficSignActor : public FCarlaActor @@ -598,21 +602,21 @@ class FTrafficLightActor : public FCarlaActor carla::rpc::ActorState InState, UWorld* World); - virtual ECarlaServerResponse SetTrafficLightState(const ETrafficLightState& State) final; + ECarlaServerResponse SetTrafficLightState(const ETrafficLightState& State) override final; - virtual ETrafficLightState GetTrafficLightState() const final; + ETrafficLightState GetTrafficLightState() const override final; - virtual UTrafficLightController* GetTrafficLightController() final; + UTrafficLightController* GetTrafficLightController() override final; - virtual ECarlaServerResponse SetLightGreenTime(float time) final; + ECarlaServerResponse SetLightGreenTime(float time) override final; - virtual ECarlaServerResponse SetLightYellowTime(float time) final; + ECarlaServerResponse SetLightYellowTime(float time) override final; - virtual ECarlaServerResponse SetLightRedTime(float time) final; + ECarlaServerResponse SetLightRedTime(float time) override final; - virtual ECarlaServerResponse FreezeTrafficLight(bool bFreeze) final; + ECarlaServerResponse FreezeTrafficLight(bool bFreeze) override final; - virtual ECarlaServerResponse ResetTrafficLightGroup() final; + ECarlaServerResponse ResetTrafficLightGroup() override final; }; @@ -626,27 +630,27 @@ class FWalkerActor : public FCarlaActor carla::rpc::ActorState InState, UWorld* World); - virtual ECarlaServerResponse SetWalkerState( + ECarlaServerResponse SetWalkerState( const FTransform& Transform, - carla::rpc::WalkerControl WalkerControl) final; + carla::rpc::WalkerControl WalkerControl) override final; - virtual ECarlaServerResponse SetActorSimulatePhysics(bool bSimulatePhysics) final; + ECarlaServerResponse SetActorSimulatePhysics(bool bSimulatePhysics) override final; - virtual ECarlaServerResponse SetActorEnableGravity(bool bEnabled) final; + ECarlaServerResponse SetActorEnableGravity(bool bEnabled) override final; - virtual ECarlaServerResponse ApplyControlToWalker(const FWalkerControl&) final; + ECarlaServerResponse ApplyControlToWalker(const FWalkerControl&) override final; - virtual ECarlaServerResponse GetWalkerControl(FWalkerControl&) final; + ECarlaServerResponse GetWalkerControl(FWalkerControl&) override final; - virtual ECarlaServerResponse GetBonesTransform(FWalkerBoneControlOut&) final; + ECarlaServerResponse GetBonesTransform(FWalkerBoneControlOut&) override final; - virtual ECarlaServerResponse SetBonesTransform(const FWalkerBoneControlIn&) final; + ECarlaServerResponse SetBonesTransform(const FWalkerBoneControlIn&) override final; - virtual ECarlaServerResponse BlendPose(float Blend); + ECarlaServerResponse BlendPose(float Blend) override final; - virtual ECarlaServerResponse GetPoseFromAnimation(); + ECarlaServerResponse GetPoseFromAnimation() override final; - virtual ECarlaServerResponse SetActorDead(); + ECarlaServerResponse SetActorDead() override final; }; class FOtherActor : public FCarlaActor diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Carla.Build.cs b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Carla.Build.cs index 3fc6b7fa333..4918af5db4f 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Carla.Build.cs +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Carla.Build.cs @@ -321,8 +321,6 @@ private void AddCarlaServerDependency(ReadOnlyTargetRules Target) if (UsingRos2) { - PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", GetLibName("carla_fastdds"))); - PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", "libfoonathan_memory-0.7.3.a")); PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", "libfastcdr.a")); PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", "libfastrtps.a")); @@ -345,6 +343,12 @@ private void AddCarlaServerDependency(ReadOnlyTargetRules Target) PublicIncludePaths.Add(LibCarlaIncludePath); PrivateIncludePaths.Add(LibCarlaIncludePath); + if ( UsingRos2 ) + { + PublicIncludePaths.Add(Path.Combine(LibCarlaIncludePath, "carla", "ros2", "ros_types")); + PrivateIncludePaths.Add(Path.Combine(LibCarlaIncludePath, "carla", "ros2", "ros_types")); + } + PublicDefinitions.Add("ASIO_NO_EXCEPTIONS"); PublicDefinitions.Add("BOOST_NO_EXCEPTIONS"); PublicDefinitions.Add("LIBCARLA_NO_EXCEPTIONS"); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEngine.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEngine.cpp index 394e89600d8..61d3bfc963c 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEngine.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEngine.cpp @@ -25,7 +25,10 @@ #include #include #include -#include +#if defined(WITH_ROS2) +# include +# include "carla/ros2/types/SensorActorDefinition.h" +#endif #include #include #include @@ -65,8 +68,10 @@ FCarlaEngine::~FCarlaEngine() { #if defined(WITH_ROS2) auto ROS2 = carla::ros2::ROS2::GetInstance(); - if (ROS2->IsEnabled()) - ROS2->Shutdown(); + if (ROS2->IsEnabled()) { + UE_LOG(LogCarla, Log, TEXT("DISABLE ROS")); + ROS2->Disable(); + } #endif FWorldDelegates::OnWorldTickStart.Remove(OnPreTickHandle); FWorldDelegates::OnWorldPostActorTick.Remove(OnPostTickHandle); @@ -77,7 +82,16 @@ FCarlaEngine::~FCarlaEngine() void FCarlaEngine::NotifyInitGame(const UCarlaSettings &Settings) { TRACE_CPUPROFILER_EVENT_SCOPE_STR(__FUNCTION__); - if (!bIsRunning) + if ( bIsRunning) { + #if defined(WITH_ROS2) + auto ROS2 = carla::ros2::ROS2::GetInstance(); + if (ROS2->IsEnabled()) { + UE_LOG(LogCarla, Log, TEXT("ROS2:: NotifyEndGame")); + ROS2->NotifyEndGame(); + } + #endif + } + else { const auto StreamingPort = Settings.StreamingPort; const auto SecondaryPort = Settings.SecondaryPort; @@ -164,10 +178,9 @@ void FCarlaEngine::NotifyInitGame(const UCarlaSettings &Settings) } case carla::multigpu::MultiGPUCommand::ENABLE_ROS: { - // get the sensor id - auto sensor_id = *(reinterpret_cast(Data.data())); + auto stream_actor_id = *(reinterpret_cast(Data.data())); // query dispatcher - Server.GetStreamingServer().EnableForROS(sensor_id); + Server.GetStreamingServer().EnableForROS(stream_actor_id); // return a 'true' bool res = true; carla::Buffer buf(reinterpret_cast(&res), (size_t) sizeof(bool)); @@ -177,10 +190,9 @@ void FCarlaEngine::NotifyInitGame(const UCarlaSettings &Settings) } case carla::multigpu::MultiGPUCommand::DISABLE_ROS: { - // get the sensor id - auto sensor_id = *(reinterpret_cast(Data.data())); + auto stream_actor_id = *(reinterpret_cast(Data.data())); // query dispatcher - Server.GetStreamingServer().DisableForROS(sensor_id); + Server.GetStreamingServer().DisableForROS(stream_actor_id); // return a 'true' bool res = true; carla::Buffer buf(reinterpret_cast(&res), (size_t) sizeof(bool)); @@ -190,10 +202,9 @@ void FCarlaEngine::NotifyInitGame(const UCarlaSettings &Settings) } case carla::multigpu::MultiGPUCommand::IS_ENABLED_ROS: { - // get the sensor id - auto sensor_id = *(reinterpret_cast(Data.data())); + auto stream_actor_id = *(reinterpret_cast(Data.data())); // query dispatcher - bool res = Server.GetStreamingServer().IsEnabledForROS(sensor_id); + bool res = Server.GetStreamingServer().IsEnabledForROS(stream_actor_id); carla::Buffer buf(reinterpret_cast(&res), (size_t) sizeof(bool)); carla::log_info("responding IS_ENABLED_ROS with: ", res); Secondary->Write(std::move(buf)); @@ -205,7 +216,7 @@ void FCarlaEngine::NotifyInitGame(const UCarlaSettings &Settings) Secondary = std::make_shared(PrimaryIP, PrimaryPort, CommandExecutor); Secondary->Connect(); // set this server in synchronous mode - bSynchronousMode = true; + Server.EnableSynchronousMode(); } else { @@ -218,18 +229,28 @@ void FCarlaEngine::NotifyInitGame(const UCarlaSettings &Settings) UE_LOG(LogCarla, Log, TEXT("New secondary connection detected")); }); } + + #if defined(WITH_ROS2) + if (Settings.ROS2) { + // create ROS2 manager + UE_LOG(LogCarla, Log, TEXT("ENABLE ROS: %s"), UTF8_TO_TCHAR(Settings.ROS2TopicVisibility?" Topics visible per default": " Topics invisible")); + auto ROS2 = carla::ros2::ROS2::GetInstance(); + ROS2->Enable(&Server, carla::streaming::detail::token_type(WorldObserver.GetToken()).get_stream_id(), + Settings.ROS2TopicVisibility?carla::ros2::ROS2::TopicVisibilityDefaultMode::eOn:carla::ros2::ROS2::TopicVisibilityDefaultMode::eOff); + Server.SetROS2TopicVisibilityDefaultEnabled(Settings.ROS2TopicVisibility); + } + #endif } - // create ROS2 manager + bMapChanged = true; + #if defined(WITH_ROS2) - if (Settings.ROS2) - { - auto ROS2 = carla::ros2::ROS2::GetInstance(); - ROS2->Enable(true); + auto ROS2 = carla::ros2::ROS2::GetInstance(); + if (ROS2->IsEnabled()) { + UE_LOG(LogCarla, Log, TEXT("ROS2:: NotifyInitGame")); + ROS2->NotifyInitGame(); } #endif - - bMapChanged = true; } void FCarlaEngine::NotifyBeginEpisode(UCarlaEpisode &Episode) @@ -265,40 +286,69 @@ void FCarlaEngine::NotifyBeginEpisode(UCarlaEpisode &Episode) Recorder->GetReplayer()->CheckPlayAfterMapLoaded(); } + #if defined(WITH_ROS2) + auto ROS2 = carla::ros2::ROS2::GetInstance(); + if (ROS2->IsEnabled()) { + UE_LOG(LogCarla, Log, TEXT("ROS2:: NotifyBeginEpisode")); + ROS2->NotifyBeginEpisode(); + } + #endif + Server.NotifyBeginEpisode(Episode); Episode.bIsPrimaryServer = bIsPrimaryServer; + } void FCarlaEngine::NotifyEndEpisode() { + #if defined(WITH_ROS2) + auto ROS2 = carla::ros2::ROS2::GetInstance(); + if (ROS2->IsEnabled()) { + UE_LOG(LogCarla, Log, TEXT("ROS2:: NotifyEndEpisode")); + ROS2->NotifyEndEpisode(); + } + #endif + Server.NotifyEndEpisode(); CurrentEpisode = nullptr; } + void FCarlaEngine::OnPreTick(UWorld *, ELevelTick TickType, float DeltaSeconds) { TRACE_CPUPROFILER_EVENT_SCOPE_STR(__FUNCTION__); if (TickType == ELevelTick::LEVELTICK_All) { - + #if defined(WITH_ROS2) + auto ROS2 = carla::ros2::ROS2::GetInstance(); + #endif if (bIsPrimaryServer) { - if (CurrentEpisode && !bSynchronousMode && SecondaryServer->HasClientsConnected()) - { - // set synchronous mode - CurrentSettings.bSynchronousMode = true; - CurrentSettings.FixedDeltaSeconds = 1 / 20.0f; - OnEpisodeSettingsChanged(CurrentSettings); - CurrentEpisode->ApplySettings(CurrentSettings); - } - // process RPC commands do { Server.RunSome(1u); + #if defined(WITH_ROS2) + if (ROS2->IsEnabled()) + { + ROS2->ProcessMessages(); + } + #endif + } + while (Server.IsSynchronousModeActive() && !Server.TickCueReceived()); + + if ( (CurrentEpisode && !Server.IsSynchronousModeActive() && SecondaryServer->HasClientsConnected()) + || ( Server.IsSynchronousModeActive() && (!CurrentSettings.FixedDeltaSeconds || !CurrentSettings.bSynchronousMode) ) ) + { + // ensure the delta seconds in this run are also considered + DeltaSeconds = 1 / 20.0f; + + CurrentSettings.bSynchronousMode = true; + CurrentSettings.FixedDeltaSeconds = DeltaSeconds; + OnEpisodeSettingsChanged(CurrentSettings); + CurrentEpisode->ApplySettings(CurrentSettings); } - while (bSynchronousMode && !Server.TickCueReceived()); } else { @@ -306,6 +356,12 @@ void FCarlaEngine::OnPreTick(UWorld *, ELevelTick TickType, float DeltaSeconds) do { Server.RunSome(1u); + #if defined(WITH_ROS2) + if (ROS2->IsEnabled()) + { + ROS2->ProcessMessages(); + } + #endif } while (!FramesToProcess.size()); } @@ -338,6 +394,13 @@ void FCarlaEngine::OnPostTick(UWorld *World, ELevelTick TickType, float DeltaSec // tick the recorder/replayer system if (GetCurrentEpisode()) { + #if defined(WITH_ROS2) + auto ROS2 = carla::ros2::ROS2::GetInstance(); + if (ROS2->IsEnabled()) + { + ROS2->ProcessDataFromUeSensorPreAction(); + } + #endif if (bIsPrimaryServer) { if (SecondaryServer->HasClientsConnected()) { @@ -377,7 +440,17 @@ void FCarlaEngine::OnPostTick(UWorld *World, ELevelTick TickType, float DeltaSec // send the worldsnapshot WorldObserver.BroadcastTick(*CurrentEpisode, DeltaSeconds, bMapChanged, LightUpdatePending); CurrentEpisode->GetSensorManager().PostPhysTick(World, TickType, DeltaSeconds); + + ResetSimulationState(); + + #if defined(WITH_ROS2) + auto ROS2 = carla::ros2::ROS2::GetInstance(); + if (ROS2->IsEnabled()) + { + ROS2->ProcessDataFromUeSensorPostAction(); + } + #endif } } @@ -385,7 +458,12 @@ void FCarlaEngine::OnEpisodeSettingsChanged(const FEpisodeSettings &Settings) { CurrentSettings = FEpisodeSettings(Settings); - bSynchronousMode = Settings.bSynchronousMode; + if (Settings.bSynchronousMode && !Server.IsSynchronousModeActive()) { + Server.EnableSynchronousMode(); + } + else if (!Settings.bSynchronousMode && Server.IsSynchronousModeActive()) { + Server.DisableSynchronousMode(); + } if (GEngine && GEngine->GameViewport) { diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEngine.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEngine.h index f36f430debc..d201ec3ad21 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEngine.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEngine.h @@ -20,7 +20,6 @@ #include #include #include -#include #include #include @@ -70,22 +69,12 @@ class FCarlaEngine : private NonCopyable static uint64_t UpdateFrameCounter() { FCarlaEngine::FrameCounter += 1; - #if defined(WITH_ROS2) - auto ROS2 = carla::ros2::ROS2::GetInstance(); - if (ROS2->IsEnabled()) - ROS2->SetFrame(FCarlaEngine::FrameCounter); - #endif return FCarlaEngine::FrameCounter; } static void ResetFrameCounter(uint64_t Value = 0) { FCarlaEngine::FrameCounter = Value; - #if defined(WITH_ROS2) - auto ROS2 = carla::ros2::ROS2::GetInstance(); - if (ROS2->IsEnabled()) - ROS2->SetFrame(FCarlaEngine::FrameCounter); - #endif } std::shared_ptr GetSecondaryServer() @@ -105,8 +94,6 @@ class FCarlaEngine : private NonCopyable bool bIsRunning = false; - bool bSynchronousMode = false; - bool bMapChanged = false; FCarlaServer Server; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.cpp index 9a2fb0f1555..be841b89d1c 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.cpp @@ -11,6 +11,9 @@ #include #include #include +#if defined(WITH_ROS2) +# include +#endif #include #include "Carla/Sensor/Sensor.h" @@ -311,6 +314,12 @@ void UCarlaEpisode::AttachActors( UActorAttacher::AttachActors(Child, Parent, InAttachmentType, SocketName); + #if defined(WITH_ROS2) + auto ROS2 = carla::ros2::ROS2::GetInstance(); + if (ROS2->IsEnabled()) { + ROS2->AttachActors(FindCarlaActor(Child)->GetActorId(), FindCarlaActor(Parent)->GetActorId()); + } + #endif if (bIsPrimaryServer) { GetFrameData().AddEvent( @@ -479,3 +488,10 @@ TPair UCarlaEpisode::SpawnActorWithInfo( return result; } + +void UCarlaEpisode::TickTimers(float DeltaSeconds) +{ + ElapsedGameTime += DeltaSeconds; + SetVisualGameTime(VisualGameTime + DeltaSeconds); +} + diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h index 5b521de1af8..f1619b12548 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h @@ -22,7 +22,6 @@ #include #include #include -#include #include #include #include @@ -171,7 +170,7 @@ class CARLA_API UCarlaEpisode : public UObject /// /// If the actor is not found or is pending kill, the returned view is /// invalid. - FCarlaActor* FindCarlaActor(FCarlaActor::IdType ActorId) + FCarlaActor* FindCarlaActor(FCarlaActor::IdType ActorId) const { return ActorDispatcher->GetActorRegistry().FindCarlaActor(ActorId); } @@ -185,12 +184,13 @@ class CARLA_API UCarlaEpisode : public UObject return ActorDispatcher->GetActorRegistry().FindCarlaActor(Actor); } - /// Get the description of the Carla actor (sensor) using specific stream id. + /// Find the actor view by StreamId /// - /// If the actor is not found returns an empty string - FString GetActorDescriptionFromStream(carla::streaming::detail::stream_id_type StreamId) + /// If the actor is not found or is pending kill, the returned view is + /// invalid. + FCarlaActor* FindCarlaActorByStreamId(carla::streaming::detail::stream_id_type StreamId) const { - return ActorDispatcher->GetActorRegistry().GetDescriptionFromStream(StreamId); + return ActorDispatcher->GetActorRegistry().FindCarlaActorByStreamId(StreamId); } // =========================================================================== @@ -357,17 +357,7 @@ class CARLA_API UCarlaEpisode : public UObject bool SetActorDead(FCarlaActor &CarlaActor); - void TickTimers(float DeltaSeconds) - { - ElapsedGameTime += DeltaSeconds; - SetVisualGameTime(VisualGameTime + DeltaSeconds); - #if defined(WITH_ROS2) - auto ROS2 = carla::ros2::ROS2::GetInstance(); - if (ROS2->IsEnabled()) - ROS2->SetTimestamp(GetElapsedGameTime()); - #endif - - } + void TickTimers(float DeltaSeconds); const uint64 Id = 0u; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/FrameData.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/FrameData.cpp index 60c95b0b882..83eb5695edc 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/FrameData.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/FrameData.cpp @@ -1014,6 +1014,7 @@ void FFrameData::ProcessReplayerAnimVehicle(CarlaRecorderAnimVehicle Vehicle) Control.bReverse = (Vehicle.Gear < 0); Control.Gear = Vehicle.Gear; Control.bManualGearShift = false; + Control.Timestamp = float(Episode->GetElapsedGameTime()); CarlaActor->ApplyControlToVehicle(Control, EVehicleInputPriority::User); } } @@ -1123,6 +1124,7 @@ bool FFrameData::ProcessReplayerFinish(bool bApplyAutopilot, bool bIgnoreHero, s Control.bReverse = false; Control.Gear = 1; Control.bManualGearShift = false; + Control.Timestamp = float(Episode->GetElapsedGameTime()); CarlaActor->ApplyControlToVehicle(Control, EVehicleInputPriority::User); } break; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayerHelper.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayerHelper.cpp index 1293b8ac15a..76766b2703d 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayerHelper.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Recorder/CarlaReplayerHelper.cpp @@ -406,6 +406,7 @@ void CarlaReplayerHelper::ProcessReplayerAnimVehicle(CarlaRecorderAnimVehicle Ve Control.bReverse = (Vehicle.Gear < 0); Control.Gear = Vehicle.Gear; Control.bManualGearShift = false; + Control.Timestamp = float(Episode->GetElapsedGameTime()); CarlaActor->ApplyControlToVehicle(Control, EVehicleInputPriority::User); } } @@ -537,6 +538,7 @@ bool CarlaReplayerHelper::ProcessReplayerFinish(bool bApplyAutopilot, bool bIgno Control.bReverse = false; Control.Gear = 1; Control.bManualGearShift = false; + Control.Timestamp = float(Episode->GetElapsedGameTime()); CarlaActor->ApplyControlToVehicle(Control, EVehicleInputPriority::User); } break; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/AsyncDataStreamImpl.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/AsyncDataStreamImpl.h index a4d4e8cb2a6..9268417e682 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/AsyncDataStreamImpl.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/AsyncDataStreamImpl.h @@ -23,9 +23,19 @@ inline FAsyncDataStreamTmpl::FAsyncDataStreamTmpl( Header([&Sensor, Timestamp]() { //check(IsInGameThread()); using Serializer = carla::sensor::s11n::SensorHeaderSerializer; + FTransform Transform = Sensor.GetActorTransform(); + FTransform RelativeTransform = Transform; + auto ParentActor = Sensor.GetAttachParentActor(); + if (ParentActor) + { + RelativeTransform = RelativeTransform.GetRelativeTransform(ParentActor->GetActorTransform()); + } return Serializer::Serialize( carla::sensor::SensorRegistry::template get::index, FCarlaEngine::GetFrameCounter(), Timestamp, - Sensor.GetActorTransform()); + Transform, + RelativeTransform, + RelativeTransform.GetRotation() + ); }()) {} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CollisionSensor.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CollisionSensor.cpp index 9c04c841ffd..524573c4509 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CollisionSensor.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CollisionSensor.cpp @@ -128,24 +128,6 @@ void ACollisionSensor::OnCollisionEvent( } CollisionRegistry.emplace_back(CurrentFrame, Actor, OtherActor); - - // ROS2 -#if defined(WITH_ROS2) - auto ROS2 = carla::ros2::ROS2::GetInstance(); - if (ROS2->IsEnabled()) - { - TRACE_CPUPROFILER_EVENT_SCOPE_STR("ROS2 Send"); - - // Retrieve the corresponding Carla actor to access its ID for collision processing - FCarlaActor* OtherCarlaActor = CurrentEpisode.FindCarlaActor(OtherActor); - - if (OtherCarlaActor) { - AActor* ParentActor = GetAttachParentActor(); - auto Transform = (ParentActor) ? GetActorTransform().GetRelativeTransform(ParentActor->GetActorTransform()) : GetActorTransform(); - ROS2->ProcessDataFromCollisionSensor(0, Transform, OtherCarlaActor->GetActorId(), carla::geom::Vector3D{NormalImpulse.X, NormalImpulse.Y, NormalImpulse.Z}, this); - } - } -#endif } void ACollisionSensor::OnActorCollisionEvent( diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.cpp index 60c5aabbb98..2dac313f2f6 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.cpp @@ -14,8 +14,7 @@ #include "CustomV2XSensor.h" #include "V2X/PathLossModel.h" -std::list ACustomV2XSensor::mV2XActorContainer; -ACustomV2XSensor::ActorV2XDataMap ACustomV2XSensor::mActorV2XDataMap; +ACustomV2XSensor::ActorV2XDataMap ACustomV2XSensor::gActorV2XDataMap; ACustomV2XSensor::ACustomV2XSensor(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) @@ -24,38 +23,30 @@ ACustomV2XSensor::ACustomV2XSensor(const FObjectInitializer &ObjectInitializer) RandomEngine = CreateDefaultSubobject(TEXT("RandomEngine")); // Init path loss model - PathLossModelObj = new PathLossModel(RandomEngine); + PathLossModelObj = new PathLossModel(RandomEngine, this); } void ACustomV2XSensor::SetOwner(AActor *Owner) { - UE_LOG(LogCarla, Warning, TEXT("CustomV2XSensor: called setowner with %p"), Owner); - if (GetOwner() != nullptr) - { - ACustomV2XSensor::mV2XActorContainer.remove(GetOwner()); - UE_LOG(LogCarla, Warning, TEXT("CustomV2XSensor: removed old owner %p"), GetOwner()); - } - Super::SetOwner(Owner); - // Store the actor into the static list if the actor details are not available - if(Owner != nullptr) - { - if (std::find(ACustomV2XSensor::mV2XActorContainer.begin(), ACustomV2XSensor::mV2XActorContainer.end(), Owner) == ACustomV2XSensor::mV2XActorContainer.end()) - { - ACustomV2XSensor::mV2XActorContainer.push_back(Owner); - UE_LOG(LogCarla, Warning, TEXT("CustomV2XSensor: added owner, length now %d"), ACustomV2XSensor::mV2XActorContainer.size()); + if(Owner != nullptr) { + UCarlaEpisode* CarlaEpisode = UCarlaStatics::GetCurrentEpisode(GetWorld()); + FCarlaActor* CarlaActor = CarlaEpisode->FindCarlaActor(Owner); + if (CarlaActor != nullptr) { + mStationId = static_cast(CarlaActor->GetActorId()); } - } +} - PathLossModelObj->SetOwner(Owner); - - UCarlaEpisode* CarlaEpisode = UCarlaStatics::GetCurrentEpisode(GetWorld()); - FCarlaActor* CarlaActor = CarlaEpisode->FindCarlaActor(Owner); - if (CarlaActor != nullptr) - { - mStationId = static_cast(CarlaActor->GetActorId()); +void ACustomV2XSensor::UpdateStationId() +{ + if ( mStationId == 0) { + UCarlaEpisode* CarlaEpisode = UCarlaStatics::GetCurrentEpisode(GetWorld()); + FCarlaActor* CarlaActor = CarlaEpisode->FindCarlaActor(this); + if (CarlaActor != nullptr) { + mStationId = static_cast(CarlaActor->GetActorId()); + } } } @@ -67,9 +58,14 @@ FActorDefinition ACustomV2XSensor::GetSensorDefinition() /* Function to add configurable parameters*/ void ACustomV2XSensor::Set(const FActorDescription &ActorDescription) { - UE_LOG(LogCarla, Warning, TEXT("CustomV2XSensor: Set function called")); Super::Set(ActorDescription); UActorBlueprintFunctionLibrary::SetCustomV2X(ActorDescription, this); + + auto Channel = ActorDescription.Variations.Find("channel_id"); + if (Channel != nullptr) + { + mChannelId = TCHAR_TO_UTF8(*Channel->Value); + } } void ACustomV2XSensor::SetPropagationParams(const float TransmitPower, @@ -106,42 +102,11 @@ void ACustomV2XSensor::PrePhysTick(float DeltaSeconds) // Clear the message created during the last sim cycle if (GetOwner()) { - ACustomV2XSensor::mActorV2XDataMap.erase(GetOwner()); - - // Step 0: Create message to send, if triggering conditions fulfilled - // this needs to be done in pre phys tick to enable synchronous reception in all other v2x sensors - // Check whether the message is generated - if (mMessageDataChanged) - { - // If message is generated store it - // make a pair of message and sending power - // if different v2x sensors send with different power, we need to store that - carla::sensor::data::CustomV2XData message_pw; - message_pw.Message = CreateCustomV2XMessage(); - - message_pw.Power = PathLossModelObj->GetTransmitPower(); - ACustomV2XSensor::mActorV2XDataMap.insert({GetOwner(), message_pw}); - } + std::lock_guard lock(v2xDataLock); + ACustomV2XSensor::gActorV2XDataMap.erase(GetSenderId()); } } -CustomV2XM_t ACustomV2XSensor::CreateCustomV2XMessage() -{ - CustomV2XM_t message = CustomV2XM_t(); - - CreateITSPduHeader(message); - std::strcpy(message.message,mMessageData.c_str()); - mMessageDataChanged = false; - return message; -} - -void ACustomV2XSensor::CreateITSPduHeader(CustomV2XM_t &message) -{ - ITSContainer::ItsPduHeader_t& header = message.header; - header.protocolVersion = mProtocolVersion; - header.messageID = mMessageId; - header.stationID = mStationId; -} /* * Function takes care of sending messages to the current actor. @@ -150,23 +115,28 @@ void ACustomV2XSensor::CreateITSPduHeader(CustomV2XM_t &message) */ void ACustomV2XSensor::PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaTime) { + // tracing after we get the lock TRACE_CPUPROFILER_EVENT_SCOPE(ACustomV2XSensor::PostPhysTick); - // Step 1: Create an actor list which has messages to send targeting this v2x sensor instance std::vector ActorPowerList; - for (const auto &pair : ACustomV2XSensor::mActorV2XDataMap) { - if (pair.first != GetOwner()) + std::lock_guard lock(v2xDataLock); + for (const auto &pair : gActorV2XDataMap) { - ActorPowerPair actor_power_pair; - actor_power_pair.first = pair.first; - // actor sending with transmit power - actor_power_pair.second = pair.second.Power; - ActorPowerList.push_back(actor_power_pair); + // only different sensors with the same ChannelId talk to each other + if ((pair.first.Actor != this) && (mChannelId == pair.first.ChannelId)) + { + ActorPowerPair actor_power_pair; + actor_power_pair.first = pair.first.Actor; + // actor sending with transmit power (identical for all messages of this tick) + actor_power_pair.second = pair.second.front().Power; + ActorPowerList.push_back(actor_power_pair); + } } } - + // Step 2: Simulate the communication for the actors in actor list to current actor. + FV2XData v2XData; if (!ActorPowerList.empty()) { UCarlaEpisode *carla_episode = UCarlaStatics::GetCurrentEpisode(GetWorld()); @@ -178,48 +148,47 @@ void ACustomV2XSensor::PostPhysTick(UWorld *World, ELevelTick TickType, float De // get registry to retrieve carla actor IDs const FActorRegistry &Registry = carla_episode->GetActorRegistry(); - ACustomV2XSensor::V2XDataList msg_received_power_list; - for (const auto &pair : actor_receivepower_map) { - carla::sensor::data::CustomV2XData send_msg_and_pw = ACustomV2XSensor::mActorV2XDataMap.at(pair.first); - carla::sensor::data::CustomV2XData received_msg_and_pw; - // sent CAM - received_msg_and_pw.Message = send_msg_and_pw.Message; - // receive power - received_msg_and_pw.Power = pair.second; - - msg_received_power_list.push_back(received_msg_and_pw); + std::lock_guard lock(v2xDataLock); + for (const auto &pair : actor_receivepower_map) + { + for ( const auto & send_msg_and_pw: gActorV2XDataMap.at({pair.first, mChannelId})) + { + carla::sensor::data::CustomV2XData received_msg_and_pw; + // sent CAM + received_msg_and_pw.Message = send_msg_and_pw.Message; + // receive power + received_msg_and_pw.Power = pair.second; + + v2XData.WriteMessage(received_msg_and_pw); + } + } } - - WriteMessageToV2XData(msg_received_power_list); } // Step 5: Send message - if (mV2XData.GetMessageCount() > 0) + if (v2XData.GetMessageCount() > 0) { auto DataStream = GetDataStream(*this); - DataStream.SerializeAndSend(*this, mV2XData, DataStream.PopBufferFromPool()); + DataStream.SerializeAndSend(*this, v2XData, DataStream.PopBufferFromPool()); } - mV2XData.Reset(); } -/* - * Function the store the message into the structure so it can be sent to python client - */ -void ACustomV2XSensor::WriteMessageToV2XData(const ACustomV2XSensor::V2XDataList &msg_received_power_list) -{ - for (const auto &elem : msg_received_power_list) - { - mV2XData.WriteMessage(elem); - } -} - - -void ACustomV2XSensor::Send(const FString message) +void ACustomV2XSensor::Send(const carla::rpc::CustomV2XBytes &data) { - //note: this is unsafe! - //should be fixed to limit length somewhere - mMessageData = TCHAR_TO_UTF8(*message); - mMessageDataChanged = true; + // we have to queue the data immediately otherwhise only one single message can be processed per frame! + std::lock_guard lock(v2xDataLock); + + UpdateStationId(); + + // make a pair of message and sending power + // if different v2x sensors send with different power, we need to store that + carla::sensor::data::CustomV2XData message_pw; + message_pw.Message.header.protocolVersion = mProtocolVersion; + message_pw.Message.header.messageID = mMessageId; + message_pw.Message.header.stationID = mStationId; + message_pw.Message.data = data; + message_pw.Power = PathLossModelObj->GetTransmitPower(); + gActorV2XDataMap.insert({GetSenderId(), V2XDataList()}).first->second.push_back(message_pw); } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.h index ced0cc28708..38f09f409d2 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CustomV2XSensor.h @@ -13,6 +13,7 @@ #include "V2X/PathLossModel.h" #include #include +#include #include "CustomV2XSensor.generated.h" @@ -22,8 +23,14 @@ class CARLA_API ACustomV2XSensor : public ASensor GENERATED_BODY() using FV2XData = carla::sensor::data::CustomV2XDataS; - using V2XDataList = std::vector; - using ActorV2XDataMap = std::map; + using V2XDataList = std::list; + struct SenderId { + AActor * Actor; + std::string ChannelId; + + bool operator < (const SenderId & other) const { return (Actor < other.Actor) && (ChannelId < other.ChannelId); } + }; + using ActorV2XDataMap = std::map; public: ACustomV2XSensor(const FObjectInitializer &ObjectInitializer); @@ -47,27 +54,21 @@ class CARLA_API ACustomV2XSensor : public ASensor virtual void PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaTime) override; void SetOwner(AActor *Owner) override; - void Send(const FString message); + void Send(const carla::rpc::CustomV2XBytes &data); private: - static std::list mV2XActorContainer; - PathLossModel *PathLossModelObj; - - //store data - static ACustomV2XSensor::ActorV2XDataMap mActorV2XDataMap; - FV2XData mV2XData; + SenderId GetSenderId() { return {this, mChannelId}; } + + // infrastructure stationID cannot be dermined before sending data, because on construction time the CARLA Actor is not yet created + void UpdateStationId(); + // global data + std::mutex v2xDataLock; + static ActorV2XDataMap gActorV2XDataMap; - //write - void WriteMessageToV2XData(const ACustomV2XSensor::V2XDataList &msg_received_power_list); + PathLossModel *PathLossModelObj; - //msg gen - void CreateITSPduHeader(CustomV2XM_t &message); - CustomV2XM_t CreateCustomV2XMessage(); const long mProtocolVersion = 2; const long mMessageId = ITSContainer::messageID_custom; - long mStationId; - std::string mMessageData; - bool mMessageDataChanged = false; - constexpr static uint16_t data_size = sizeof(CustomV2XM_t::message); - + long mStationId {0}; + std::string mChannelId; }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/DVSCamera.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/DVSCamera.cpp index 42afd61aa40..ea79b74da7d 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/DVSCamera.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/DVSCamera.cpp @@ -15,7 +15,6 @@ #include "Actor/ActorBlueprintFunctionLibrary.h" #include -#include "carla/ros2/ROS2.h" #include #include #include @@ -158,29 +157,21 @@ void ADVSCamera::PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaTim /** DVS Simulator **/ ADVSCamera::DVSEventArray events = this->Simulation(DeltaTime); - auto Stream = GetDataStream(*this); - auto Buff = Stream.PopBufferFromPool(); - - // serialize data - carla::Buffer BufferReady(carla::sensor::SensorRegistry::Serialize(*this, events, std::move(Buff))); - carla::SharedBufferView BufView = carla::BufferView::CreateFrom(std::move(BufferReady)); - - // ROS2 - #if defined(WITH_ROS2) - auto ROS2 = carla::ros2::ROS2::GetInstance(); - if (ROS2->IsEnabled()) - { - TRACE_CPUPROFILER_EVENT_SCOPE_STR("ROS2 Send"); - AActor* ParentActor = GetAttachParentActor(); - auto Transform = (ParentActor) ? GetActorTransform().GetRelativeTransform(ParentActor->GetActorTransform()) : Stream.GetSensorTransform(); - ROS2->ProcessDataFromDVS(Stream.GetSensorType(), Transform, BufView, this); - } - #endif if (events.size() > 0) { - TRACE_CPUPROFILER_EVENT_SCOPE_STR("ADVSCamera Stream Send"); - /** Send the events **/ - Stream.Send(*this, BufView); + auto Stream = GetDataStream(*this); + auto Buff = Stream.PopBufferFromPool(); + + // serialize data + carla::Buffer BufferReady(carla::sensor::SensorRegistry::Serialize(*this, events, std::move(Buff))); + carla::SharedBufferView BufView = carla::BufferView::CreateFrom(std::move(BufferReady)); + + if (events.size() > 0) + { + TRACE_CPUPROFILER_EVENT_SCOPE_STR("ADVSCamera Stream Send"); + /** Send the events **/ + Stream.Send(*this, BufView); + } } } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/GnssSensor.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/GnssSensor.cpp index 61141e04bd7..c52d41e052f 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/GnssSensor.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/GnssSensor.cpp @@ -13,7 +13,6 @@ #include #include "carla/geom/Vector3D.h" -#include "carla/ros2/ROS2.h" #include AGnssSensor::AGnssSensor(const FObjectInitializer &ObjectInitializer) @@ -59,17 +58,6 @@ void AGnssSensor::PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaSe auto Stream = GetDataStream(*this); - // ROS2 - #if defined(WITH_ROS2) - auto ROS2 = carla::ros2::ROS2::GetInstance(); - if (ROS2->IsEnabled()) - { - TRACE_CPUPROFILER_EVENT_SCOPE_STR("ROS2 Send"); - AActor* ParentActor = GetAttachParentActor(); - auto Transform = (ParentActor) ? GetActorTransform().GetRelativeTransform(ParentActor->GetActorTransform()) : GetActorTransform(); - ROS2->ProcessDataFromGNSS(Stream.GetSensorType(), Transform, carla::geom::GeoLocation{Latitude, Longitude, Altitude}, this); - } - #endif { TRACE_CPUPROFILER_EVENT_SCOPE_STR("AGnssSensor Stream Send"); Stream.SerializeAndSend(*this, carla::geom::GeoLocation{Latitude, Longitude, Altitude}); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/HSSLidar.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/HSSLidar.cpp index 136ccfd4b00..1f94857e8b6 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/HSSLidar.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/HSSLidar.cpp @@ -14,7 +14,6 @@ #include #include "carla/geom/Math.h" -#include "carla/ros2/ROS2.h" #include "carla/geom/Location.h" #include @@ -69,19 +68,6 @@ void AHSSLidar::PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaTime TRACE_CPUPROFILER_EVENT_SCOPE_STR("Send Stream"); DataStream.SerializeAndSend(*this, LidarData, DataStream.PopBufferFromPool()); } - // ROS2 - #if defined(WITH_ROS2) - auto ROS2 = carla::ros2::ROS2::GetInstance(); - if (ROS2->IsEnabled()) - { - TRACE_CPUPROFILER_EVENT_SCOPE_STR("ROS2 Send"); - AActor* ParentActor = GetAttachParentActor(); - auto Transform = (ParentActor) ? GetActorTransform().GetRelativeTransform(ParentActor->GetActorTransform()) : GetActorTransform(); - ROS2->ProcessDataFromLidar(DataStream.GetSensorType(), Transform, LidarData, this); - } - #endif - - } float AHSSLidar::ComputeIntensity(const FSemanticDetection& RawDetection) const diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/InertialMeasurementUnit.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/InertialMeasurementUnit.cpp index d6922a92d84..8c0fafba529 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/InertialMeasurementUnit.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/InertialMeasurementUnit.cpp @@ -13,7 +13,6 @@ #include #include "carla/geom/Math.h" -#include "carla/ros2/ROS2.h" #include #include "Carla/Game/CarlaStatics.h" @@ -192,18 +191,6 @@ void AInertialMeasurementUnit::PostPhysTick(UWorld *World, ELevelTick TickType, auto Stream = GetDataStream(*this); - // ROS2 - #if defined(WITH_ROS2) - auto ROS2 = carla::ros2::ROS2::GetInstance(); - if (ROS2->IsEnabled()) - { - TRACE_CPUPROFILER_EVENT_SCOPE_STR("ROS2 Send"); - AActor* ParentActor = GetAttachParentActor(); - auto Transform = (ParentActor) ? GetActorTransform().GetRelativeTransform(ParentActor->GetActorTransform()) : GetActorTransform(); - ROS2->ProcessDataFromIMU(Stream.GetSensorType(), Transform, Accelerometer, Gyroscope, Compass, this); - } - #endif - { TRACE_CPUPROFILER_EVENT_SCOPE(AInertialMeasurementUnit::PostPhysTick); Stream.SerializeAndSend(*this, Accelerometer, Gyroscope, Compass); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/ObstacleDetectionSensor.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/ObstacleDetectionSensor.cpp index c74b72bd2cc..54dd5d26ee4 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/ObstacleDetectionSensor.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/ObstacleDetectionSensor.cpp @@ -13,10 +13,6 @@ #include "Carla/Game/CarlaGameInstance.h" #include "Carla/Game/CarlaGameModeBase.h" -#include -#include "carla/ros2/ROS2.h" -#include - AObstacleDetectionSensor::AObstacleDetectionSensor(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) { @@ -142,18 +138,6 @@ void AObstacleDetectionSensor::OnObstacleDetectionEvent( auto DataStream = GetDataStream(*this); - // ROS2 - #if defined(WITH_ROS2) - auto ROS2 = carla::ros2::ROS2::GetInstance(); - if (ROS2->IsEnabled()) - { - TRACE_CPUPROFILER_EVENT_SCOPE_STR("ROS2 Send"); - AActor* ParentActor = GetAttachParentActor(); - auto Transform = (ParentActor) ? GetActorTransform().GetRelativeTransform(ParentActor->GetActorTransform()) : GetActorTransform(); - ROS2->ProcessDataFromObstacleDetection(DataStream.GetSensorType(), Transform, Actor, OtherActor, HitDistance/100.0f, this); - } - #endif - DataStream.SerializeAndSend(*this, Episode.SerializeActor(Actor), Episode.SerializeActor(OtherActor), diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/PixelReader.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/PixelReader.h index ac033829643..7d645154a5c 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/PixelReader.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/PixelReader.h @@ -183,22 +183,6 @@ void FPixelReader::SendPixelsInRenderThread(TSensor &Sensor, bool use16BitFormat carla::Buffer BufferReady(std::move(carla::sensor::SensorRegistry::Serialize(Sensor, std::move(Buffer)))); carla::SharedBufferView BufView = carla::BufferView::CreateFrom(std::move(BufferReady)); - // ROS2 - #if defined(WITH_ROS2) - auto ROS2 = carla::ros2::ROS2::GetInstance(); - if (ROS2->IsEnabled()) - { - TRACE_CPUPROFILER_EVENT_SCOPE_STR("ROS2 Send PixelReader"); - // auto StreamId = carla::streaming::detail::token_type(Sensor.GetToken()).get_stream_id(); - auto Res = std::async(std::launch::async, [&Sensor, ROS2, &Stream, BufView]() - { - AActor* ParentActor = Sensor.GetAttachParentActor(); - auto Transform = (ParentActor) ? Sensor.GetActorTransform().GetRelativeTransform(ParentActor->GetActorTransform()) : Stream.GetSensorTransform(); - ROS2->ProcessDataFromCamera(Stream.GetSensorType(), Transform, BufView, &Sensor); - }); - } - #endif - // network SCOPE_CYCLE_COUNTER(STAT_CarlaSensorStreamSend); TRACE_CPUPROFILER_EVENT_SCOPE_STR("Stream Send"); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Radar.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Radar.cpp index 3b28a39d3da..b11fa7ad959 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Radar.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Radar.cpp @@ -14,7 +14,6 @@ #include #include "carla/geom/Math.h" -#include "carla/ros2/ROS2.h" #include FActorDefinition ARadar::GetSensorDefinition() @@ -79,18 +78,6 @@ void ARadar::PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaTime) auto DataStream = GetDataStream(*this); - // ROS2 - #if defined(WITH_ROS2) - auto ROS2 = carla::ros2::ROS2::GetInstance(); - if (ROS2->IsEnabled()) - { - TRACE_CPUPROFILER_EVENT_SCOPE_STR("ROS2 Send"); - AActor* ParentActor = GetAttachParentActor(); - auto Transform = (ParentActor) ? GetActorTransform().GetRelativeTransform(ParentActor->GetActorTransform()) : GetActorTransform(); - ROS2->ProcessDataFromRadar(DataStream.GetSensorType(), Transform, RadarData, this); - } - #endif - { TRACE_CPUPROFILER_EVENT_SCOPE_STR("Send Stream"); DataStream.SerializeAndSend(*this, RadarData, DataStream.PopBufferFromPool()); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastLidar.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastLidar.cpp index db5e2c72810..ee02a11f62c 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastLidar.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastLidar.cpp @@ -13,7 +13,6 @@ #include #include "carla/geom/Math.h" -#include "carla/ros2/ROS2.h" #include "carla/geom/Location.h" #include @@ -67,19 +66,6 @@ void ARayCastLidar::PostPhysTick(UWorld *World, ELevelTick TickType, float Delta TRACE_CPUPROFILER_EVENT_SCOPE_STR("Send Stream"); DataStream.SerializeAndSend(*this, LidarData, DataStream.PopBufferFromPool()); } - // ROS2 - #if defined(WITH_ROS2) - auto ROS2 = carla::ros2::ROS2::GetInstance(); - if (ROS2->IsEnabled()) - { - TRACE_CPUPROFILER_EVENT_SCOPE_STR("ROS2 Send"); - AActor* ParentActor = GetAttachParentActor(); - auto Transform = (ParentActor) ? GetActorTransform().GetRelativeTransform(ParentActor->GetActorTransform()) : GetActorTransform(); - ROS2->ProcessDataFromLidar(DataStream.GetSensorType(), Transform, LidarData, this); - } - #endif - - } float ARayCastLidar::ComputeIntensity(const FSemanticDetection& RawDetection) const diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastSemanticLidar.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastSemanticLidar.cpp index e1c58a07b56..40b069dd502 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastSemanticLidar.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastSemanticLidar.cpp @@ -12,7 +12,6 @@ #include #include "carla/geom/Math.h" -#include "carla/ros2/ROS2.h" #include #include "DrawDebugHelpers.h" @@ -71,22 +70,10 @@ void ARayCastSemanticLidar::PostPhysTick(UWorld *World, ELevelTick TickType, flo SimulateLidar(DeltaTime); auto DataStream = GetDataStream(*this); - auto SensorTransform = DataStream.GetSensorTransform(); { TRACE_CPUPROFILER_EVENT_SCOPE_STR("Send Stream"); DataStream.SerializeAndSend(*this, SemanticLidarData, DataStream.PopBufferFromPool()); } - // ROS2 - #if defined(WITH_ROS2) - auto ROS2 = carla::ros2::ROS2::GetInstance(); - if (ROS2->IsEnabled()) - { - TRACE_CPUPROFILER_EVENT_SCOPE_STR("ROS2 Send"); - AActor* ParentActor = GetAttachParentActor(); - auto Transform = (ParentActor) ? GetActorTransform().GetRelativeTransform(ParentActor->GetActorTransform()) : GetActorTransform(); - ROS2->ProcessDataFromSemanticLidar(DataStream.GetSensorType(), Transform, SemanticLidarData, this); - } - #endif } void ARayCastSemanticLidar::SimulateLidar(const float DeltaTime) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.cpp index fed90aad003..290a23ec1c9 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.cpp @@ -14,7 +14,7 @@ #include static const float scLowFrequencyContainerInterval = 0.5; -ITSContainer::SpeedValue_t CaService::BuildSpeedValue(const float vel) +ITSContainer::SpeedValue_t CaService::BuildSpeedValue(const float vel)const { static const float lower = 0.0; // meter_per_second static const float upper = 163.82; // meter_per_second @@ -27,7 +27,7 @@ ITSContainer::SpeedValue_t CaService::BuildSpeedValue(const float vel) else if (vel >= lower) { // to cm per second - speed = std::round(vel * 100.0) * ITSContainer::SpeedValue_oneCentimeterPerSec; + speed = std::round(vel * 100.0) * static_cast(ITSContainer::SpeedValue_oneCentimeterPerSec); } return speed; } @@ -43,9 +43,8 @@ CaService::CaService(URandomEngine *random_engine) mGenerationDelta0 = std::chrono::duration_cast(start_Point - ref_point); } -void CaService::SetOwner(UWorld *world, AActor *Owner) +void CaService::SetActor(UWorld *world, AActor *Owner) { - UE_LOG(LogCarla, Warning, TEXT("CaService:SetOwner function called")); mWorld = world; mCarlaEpisode = UCarlaStatics::GetCurrentEpisode(world); @@ -55,12 +54,12 @@ void CaService::SetOwner(UWorld *world, AActor *Owner) mCarlaEpisode = UCarlaStatics::GetCurrentEpisode(mWorld); mCarlaActor = mCarlaEpisode->FindCarlaActor(Owner); + mVehicle = nullptr; if (mCarlaActor != nullptr) { - mVehicle = Cast(Owner); - if (mCarlaActor->GetActorType() == FCarlaActor::ActorType::Vehicle) { + mVehicle = Cast(Owner); UE_LOG(LogCarla, Warning, TEXT("CaService:Initialize Vehicle type")); mLastCamTimeStamp = mCarlaEpisode->GetElapsedGameTime() - mGenCamMax; @@ -77,7 +76,8 @@ void CaService::SetOwner(UWorld *world, AActor *Owner) mLastCamHeading = {0, 0, 0}; } else if ((mCarlaActor->GetActorType() == FCarlaActor::ActorType::TrafficLight) || - (mCarlaActor->GetActorType() == FCarlaActor::ActorType::TrafficSign)) + (mCarlaActor->GetActorType() == FCarlaActor::ActorType::TrafficSign)|| + (mCarlaActor->GetActorType() == FCarlaActor::ActorType::Sensor)) { mGenerationInterval = 0.5; mLastCamTimeStamp = -mGenerationInterval; @@ -85,8 +85,9 @@ void CaService::SetOwner(UWorld *world, AActor *Owner) } mStationId = static_cast(mCarlaActor->GetActorId()); - mStationType = GetStationType(); } + mStationType = GetStationType(); + UE_LOG(LogCarla, Warning, TEXT("CaService:Initialize station type"), mStationType); } void CaService::SetParams(const float GenCamMin, const float GenCamMax, const bool FixedRate) @@ -128,7 +129,7 @@ bool CaService::Trigger(float DeltaSeconds) /* * Function to provide CAM message to other objects if necessary */ -CAM_t CaService::GetCamMessage() +CAM_t CaService::GetCamMessage()const { return mCAMMessage; } @@ -175,31 +176,34 @@ bool CaService::CheckTriggeringConditions(float DeltaSeconds) bool CaService::CheckPositionDelta(float DeltaSeconds) { - // If position change is more the 4m - VehiclePosition = mVehicle->GetActorLocation(); - double Distance = FVector::Distance(VehiclePosition, mLastCamPosition) / 100.0f; // From cm to m - if (Distance > 4.0f) - { - return true; + if ( mVehicle != nullptr ) { + // If position change is more the 4m + VehiclePosition = mVehicle->GetActorLocation(); + double Distance = FVector::Distance(VehiclePosition, mLastCamPosition) / 100.0f; // From cm to m + if (Distance > 4.0f) + { + return true; + } } return false; } bool CaService::CheckSpeedDelta(float DeltaSeconds) { - VehicleSpeed = mVehicle->GetVehicleForwardSpeed() / 100.0f; // From cm/s to m/s - float DeltaSpeed = std::abs(VehicleSpeed - mLastCamSpeed); + if ( mVehicle != nullptr ) { + VehicleSpeed = mVehicle->GetVehicleForwardSpeed() / 100.0f; // From cm/s to m/s + float DeltaSpeed = std::abs(VehicleSpeed - mLastCamSpeed); - // Speed differance is greater than 0.5m/s - if (DeltaSpeed > 0.5) - { - return true; + // Speed differance is greater than 0.5m/s + if (DeltaSpeed > 0.5) + { + return true; + } } - return false; } -double CaService::GetFVectorAngle(const FVector &a, const FVector &b) +double CaService::GetFVectorAngle(const FVector &a, const FVector &b)const { double Dot = a.X * b.X + a.Y * b.Y + a.Z * b.Z; return std::acos(Dot / (a.Size() * b.Size())); @@ -215,75 +219,80 @@ void CaService::GenerateCamMessage(float DeltaTime) } // Function to get the station type -ITSContainer::StationType_t CaService::GetStationType() +ITSContainer::StationType_t CaService::GetStationType()const { - check(mActorOwner != nullptr); - mCarlaEpisode = UCarlaStatics::GetCurrentEpisode(mWorld); - mCarlaActor = mCarlaEpisode->FindCarlaActor(mActorOwner); ITSContainer::StationType_t stationType = ITSContainer::StationType_unknown; // return unknown if carla actor is gone if (mCarlaActor == nullptr) { return static_cast(stationType); } - auto Tag = ATagger::GetTagOfTaggedComponent(*mVehicle->GetMesh()); - switch (Tag) - { - case crp::CityObjectLabel::None: - stationType = ITSContainer::StationType_unknown; - break; - case crp::CityObjectLabel::Pedestrians: - stationType = ITSContainer::StationType_pedestrian; - break; - case crp::CityObjectLabel::Bicycle: - stationType = ITSContainer::StationType_cyclist; - break; - case crp::CityObjectLabel::Motorcycle: - stationType = ITSContainer::StationType_motorcycle; - break; - case crp::CityObjectLabel::Car: - stationType = ITSContainer::StationType_passengerCar; - break; - case crp::CityObjectLabel::Bus: - stationType = ITSContainer::StationType_bus; - break; - // TODO Modify this in future is CARLA adds difference truck - case crp::CityObjectLabel::Truck: - stationType = ITSContainer::StationType_lightTruck; - break; - case crp::CityObjectLabel::Buildings: - case crp::CityObjectLabel::Walls: - case crp::CityObjectLabel::Fences: - case crp::CityObjectLabel::Poles: - case crp::CityObjectLabel::TrafficLight: - case crp::CityObjectLabel::TrafficSigns: - stationType = ITSContainer::StationType_roadSideUnit; - break; - case crp::CityObjectLabel::Train: - stationType = ITSContainer::StationType_tram; - break; - default: - stationType = ITSContainer::StationType_unknown; - } + if ( mVehicle!= nullptr ) { + auto Tag = ATagger::GetTagOfTaggedComponent(*mVehicle->GetMesh()); - // Can improve this later for different special vehicles once carla implements it - FCarlaActor::ActorType Type = mCarlaActor->GetActorType(); - if (Type == FCarlaActor::ActorType::Vehicle) - { - if (mCarlaActor->GetActorInfo()->Description.Variations.Contains("special_type")) + switch (Tag) { - std::string special_type = carla::rpc::FromFString(*mCarlaActor->GetActorInfo()->Description.Variations["special_type"].Value); - if (special_type.compare("emergency") == 0) + case crp::CityObjectLabel::None: + stationType = ITSContainer::StationType_unknown; + break; + case crp::CityObjectLabel::Pedestrians: + stationType = ITSContainer::StationType_pedestrian; + break; + case crp::CityObjectLabel::Bicycle: + stationType = ITSContainer::StationType_cyclist; + break; + case crp::CityObjectLabel::Motorcycle: + stationType = ITSContainer::StationType_motorcycle; + break; + case crp::CityObjectLabel::Car: + stationType = ITSContainer::StationType_passengerCar; + break; + case crp::CityObjectLabel::Bus: + stationType = ITSContainer::StationType_bus; + break; + // TODO Modify this in future is CARLA adds difference truck + case crp::CityObjectLabel::Truck: + stationType = ITSContainer::StationType_lightTruck; + break; + case crp::CityObjectLabel::Buildings: + case crp::CityObjectLabel::Walls: + case crp::CityObjectLabel::Fences: + case crp::CityObjectLabel::Poles: + case crp::CityObjectLabel::TrafficLight: + case crp::CityObjectLabel::TrafficSigns: + stationType = ITSContainer::StationType_roadSideUnit; + break; + case crp::CityObjectLabel::Train: + stationType = ITSContainer::StationType_tram; + break; + default: + stationType = ITSContainer::StationType_unknown; + } + + // Can improve this later for different special vehicles once carla implements it + FCarlaActor::ActorType Type = mCarlaActor->GetActorType(); + if (Type == FCarlaActor::ActorType::Vehicle) + { + if (mCarlaActor->GetActorInfo()->Description.Variations.Contains("special_type")) { - stationType = ITSContainer::StationType_specialVehicles; + std::string special_type = carla::rpc::FromFString(*mCarlaActor->GetActorInfo()->Description.Variations["special_type"].Value); + if (special_type.compare("emergency") == 0) + { + stationType = ITSContainer::StationType_specialVehicles; + } } } } + else { + // not a vehicle => RSU + stationType = ITSContainer::StationType_roadSideUnit; + } + return static_cast(stationType); } -FVector CaService::GetReferencePosition() +FVector CaService::GetReferencePosition()const { FVector RefPos; carla::geom::Location ActorLocation = mActorOwner->GetActorLocation(); @@ -311,7 +320,7 @@ FVector CaService::GetReferencePosition() return RefPos; } -float CaService::GetHeading() +float CaService::GetHeading()const { // Magnetometer: orientation with respect to the North in rad const FVector CarlaNorthVector = FVector(0.0f, -1.0f, 0.0f); @@ -337,11 +346,10 @@ float CaService::GetHeading() } // Function to get the vehicle role -long CaService::GetVehicleRole() +long CaService::GetVehicleRole()const { long VehicleRole = ITSContainer::VehicleRole_default; - long StationType = GetStationType(); - switch (StationType) + switch (mStationType) { case ITSContainer::StationType_cyclist: case ITSContainer::StationType_moped: @@ -396,7 +404,7 @@ void CaService::AddCooperativeAwarenessMessage(CAMContainer::CoopAwareness_t &Co { // TODO no container available for Pedestrains } - else + else if (CoopAwarenessMessage.camParameters.basicContainer.stationType != ITSContainer::StationType_unknown) { // BasicVehicleContainer AddBasicVehicleContainerHighFrequency(CoopAwarenessMessage.camParameters.highFrequencyContainer, DeltaTime); @@ -423,12 +431,12 @@ void CaService::AddBasicContainer(CAMContainer::BasicContainer_t &BasicContainer /* CamParameters ReferencePosition */ FVector RefPos = GetReferencePosition(); - BasicContainer.referencePosition.latitude = std::round(RefPos.X * 1e6) * ITSContainer::Latitude_oneMicroDegreeNorth; - BasicContainer.referencePosition.longitude = std::round(RefPos.Y * 1e6) * ITSContainer::Longitude_oneMicroDegreeEast; + BasicContainer.referencePosition.latitude = std::round(RefPos.X * 1e6) * static_cast(ITSContainer::Latitude_oneMicroDegreeNorth); + BasicContainer.referencePosition.longitude = std::round(RefPos.Y * 1e6) * static_cast(ITSContainer::Longitude_oneMicroDegreeEast); BasicContainer.referencePosition.positionConfidenceEllipse.semiMajorConfidence = ITSContainer::SemiAxisLength_unavailable; BasicContainer.referencePosition.positionConfidenceEllipse.semiMinorConfidence = ITSContainer::SemiAxisLength_unavailable; BasicContainer.referencePosition.positionConfidenceEllipse.semiMajorOrientation = ITSContainer::HeadingValue_unavailable; - BasicContainer.referencePosition.altitude.altitudeValue = std::round(RefPos.Z * 100.0) * ITSContainer::AltitudeValue_oneCentimeter; + BasicContainer.referencePosition.altitude.altitudeValue = std::round(RefPos.Z * 100.0) * static_cast(ITSContainer::AltitudeValue_oneCentimeter); BasicContainer.referencePosition.altitude.altitudeConfidence = ITSContainer::AltitudeConfidence_unavailable; } @@ -469,6 +477,10 @@ void CaService::SetYawrateDeviation(const float noise_yawrate_stddev, const floa void CaService::AddBasicVehicleContainerHighFrequency(CAMContainer::HighFrequencyContainer_t &hfc, float DeltaTime) { + if ( mVehicle == nullptr ) { + return; + } + hfc.present = CAMContainer::HighFrequencyContainer_PR_basicVehicleContainerHighFrequency; CAMContainer::BasicVehicleContainerHighFrequency_t &bvc = hfc.basicVehicleContainerHighFrequency; // heading @@ -496,7 +508,7 @@ void CaService::AddBasicVehicleContainerHighFrequency(CAMContainer::HighFrequenc // limit changes if (lonAccelValue >= -160.0 && lonAccelValue <= 161.0) { - bvc.longitudinalAcceleration.longitudinalAccelerationValue = std::round(lonAccelValue) * ITSContainer::LongitudinalAccelerationValue_pointOneMeterPerSecSquaredForward; + bvc.longitudinalAcceleration.longitudinalAccelerationValue = std::round(lonAccelValue) * static_cast(ITSContainer::LongitudinalAccelerationValue_pointOneMeterPerSecSquaredForward); } else { @@ -510,7 +522,7 @@ void CaService::AddBasicVehicleContainerHighFrequency(CAMContainer::HighFrequenc bvc.curvatureCalculationMode = ITSContainer::CurvatureCalculationMode_yarRateUsed; // yaw rate is in rad/s --> to centidegree per second - bvc.yawRate.yawRateValue = std::round(carla::geom::Math::ToDegrees(ComputeYawRate()) * 100.0) * ITSContainer::YawRateValue_degSec_000_01ToLeft; + bvc.yawRate.yawRateValue = std::round(carla::geom::Math::ToDegrees(ComputeYawRate()) * 100.0) * static_cast(ITSContainer::YawRateValue_degSec_000_01ToLeft); if (bvc.yawRate.yawRateValue < -32766 || bvc.yawRate.yawRateValue > 32766) { bvc.yawRate.yawRateValue = ITSContainer::YawRateValue_unavailable; @@ -522,7 +534,7 @@ void CaService::AddBasicVehicleContainerHighFrequency(CAMContainer::HighFrequenc const double latAccelValue = Accel.y * 10.0; // m/s to 0.1 m/s if (latAccelValue >= -160.0 && latAccelValue <= 161.0) { - bvc.lateralAcceleration.lateralAccelerationValue = std::round(latAccelValue) * ITSContainer::LateralAccelerationValue_pointOneMeterPerSecSquaredToLeft; + bvc.lateralAcceleration.lateralAccelerationValue = std::round(latAccelValue) * static_cast(ITSContainer::LateralAccelerationValue_pointOneMeterPerSecSquaredToLeft); } else { @@ -534,7 +546,7 @@ void CaService::AddBasicVehicleContainerHighFrequency(CAMContainer::HighFrequenc const double vertAccelValue = Accel.z * 10.0; // m/s to 0.1 m/s if (vertAccelValue >= -160.0 && vertAccelValue <= 161.0) { - bvc.verticalAcceleration.verticalAccelerationValue = std::round(vertAccelValue) * ITSContainer::VerticalAccelerationValue_pointOneMeterPerSecSquaredUp; + bvc.verticalAcceleration.verticalAccelerationValue = std::round(vertAccelValue) * static_cast(ITSContainer::VerticalAccelerationValue_pointOneMeterPerSecSquaredUp); } else { @@ -551,7 +563,7 @@ void CaService::AddBasicVehicleContainerHighFrequency(CAMContainer::HighFrequenc } const carla::geom::Vector3D CaService::ComputeAccelerometerNoise( - const FVector &Accelerometer) + const FVector &Accelerometer)const { // Normal (or Gaussian or Gauss) distribution will be used as noise function. // A mean of 0.0 is used as a first parameter, the standard deviation is @@ -566,61 +578,66 @@ const carla::geom::Vector3D CaService::ComputeAccelerometerNoise( carla::geom::Vector3D CaService::ComputeAccelerometer( const float DeltaTime) { - // Used to convert from UE4's cm to meters - constexpr float TO_METERS = 1e-2; - // Earth's gravitational acceleration is approximately 9.81 m/s^2 - constexpr float GRAVITY = 9.81f; + carla::geom::Vector3D Accelerometer(0.,0.,0.); - // 2nd derivative of the polynomic (quadratic) interpolation - // using the point in current time and two previous steps: - // d2[i] = -2.0*(y1/(h1*h2)-y2/((h2+h1)*h2)-y0/(h1*(h2+h1))) - const FVector CurrentLocation = mVehicle->GetActorLocation(); + if ( mVehicle != nullptr ) { + // Used to convert from UE4's cm to meters + constexpr float TO_METERS = 1e-2; + // Earth's gravitational acceleration is approximately 9.81 m/s^2 + constexpr float GRAVITY = 9.81f; - const FVector Y2 = PrevLocation[0]; - const FVector Y1 = PrevLocation[1]; - const FVector Y0 = CurrentLocation; - const float H1 = DeltaTime; - const float H2 = PrevDeltaTime; + // 2nd derivative of the polynomic (quadratic) interpolation + // using the point in current time and two previous steps: + // d2[i] = -2.0*(y1/(h1*h2)-y2/((h2+h1)*h2)-y0/(h1*(h2+h1))) + const FVector CurrentLocation = mVehicle->GetActorLocation(); - const float H1AndH2 = H2 + H1; - const FVector A = Y1 / (H1 * H2); - const FVector B = Y2 / (H2 * (H1AndH2)); - const FVector C = Y0 / (H1 * (H1AndH2)); - FVector FVectorAccelerometer = TO_METERS * -2.0f * (A - B - C); + const FVector Y2 = PrevLocation[0]; + const FVector Y1 = PrevLocation[1]; + const FVector Y0 = CurrentLocation; + const float H1 = DeltaTime; + const float H2 = PrevDeltaTime; - // Update the previous locations - PrevLocation[0] = PrevLocation[1]; - PrevLocation[1] = CurrentLocation; - PrevDeltaTime = DeltaTime; + const float H1AndH2 = H2 + H1; + const FVector A = Y1 / (H1 * H2); + const FVector B = Y2 / (H2 * (H1AndH2)); + const FVector C = Y0 / (H1 * (H1AndH2)); + FVector FVectorAccelerometer = TO_METERS * -2.0f * (A - B - C); - // Add gravitational acceleration - FVectorAccelerometer.Z += GRAVITY; + // Update the previous locations + PrevLocation[0] = PrevLocation[1]; + PrevLocation[1] = CurrentLocation; + PrevDeltaTime = DeltaTime; - FQuat ImuRotation = mActorOwner->GetRootComponent()->GetComponentTransform().GetRotation(); - FVectorAccelerometer = ImuRotation.UnrotateVector(FVectorAccelerometer); + // Add gravitational acceleration + FVectorAccelerometer.Z += GRAVITY; - // Cast from FVector to our Vector3D to correctly send the data in m/s^2 - // and apply the desired noise function, in this case a normal distribution - const carla::geom::Vector3D Accelerometer = - ComputeAccelerometerNoise(FVectorAccelerometer); + FQuat ImuRotation = mActorOwner->GetRootComponent()->GetComponentTransform().GetRotation(); + FVectorAccelerometer = ImuRotation.UnrotateVector(FVectorAccelerometer); + // Cast from FVector to our Vector3D to correctly send the data in m/s^2 + // and apply the desired noise function, in this case a normal distribution + Accelerometer = ComputeAccelerometerNoise(FVectorAccelerometer); + } return Accelerometer; } -float CaService::ComputeSpeed() +float CaService::ComputeSpeed()const { + float speed = 0.; + if ( mVehicle != nullptr ) { + speed = mVehicle->GetVehicleForwardSpeed() / 100.0f; - const float speed = mVehicle->GetVehicleForwardSpeed() / 100.0f; - - // Normal (or Gaussian or Gauss) distribution and a bias will be used as - // noise function. - // A mean of 0.0 is used as a first parameter.The standard deviation and the - // bias are determined by the client - constexpr float Mean = 0.0f; - return boost::algorithm::clamp(speed + mRandomEngine->GetNormalDistribution(Mean, VelocityDeviation), 0.0f, std::numeric_limits::max()); + // Normal (or Gaussian or Gauss) distribution and a bias will be used as + // noise function. + // A mean of 0.0 is used as a first parameter.The standard deviation and the + // bias are determined by the client + constexpr float Mean = 0.0f; + speed = boost::algorithm::clamp(speed + mRandomEngine->GetNormalDistribution(Mean, VelocityDeviation), 0.0f, std::numeric_limits::max()); + } + return speed; } -float CaService::ComputeYawRate() +float CaService::ComputeYawRate()const { check(mActorOwner != nullptr); const FVector AngularVelocity = @@ -641,7 +658,7 @@ float CaService::ComputeYawRate() } const float CaService::ComputeYawNoise( - const FVector &Gyroscope) + const FVector &Gyroscope)const { // Normal (or Gaussian or Gauss) distribution and a bias will be used as // noise function. @@ -676,9 +693,9 @@ void CaService::AddRSUContainerHighFrequency(CAMContainer::HighFrequencyContaine CAMContainer::RSUContainerHighFrequency_t &rsu = hfc.rsuContainerHighFrequency; // TODO For future implementation ITSContainer::ProtectedCommunicationZonesRSU_t PCZR - uint8_t ProtectedZoneDataLength = 16; // Maximum number of elements in path history - - for (uint8_t i = 0; i <= ProtectedZoneDataLength; ++i) + uint8_t const ProtectedZoneDataLength = rsu.protectedCommunicationZonesRSU.data.size(); // Maximum number of elements in path history + rsu.protectedCommunicationZonesRSU.ProtectedCommunicationZoneCount = 0; + for (uint8_t i = 0; i < ProtectedZoneDataLength; ++i) { ITSContainer::ProtectedCommunicationZone_t PCZ; PCZ.protectedZoneType = ITSContainer::ProtectedZoneType_cenDsrcTolling; @@ -687,13 +704,17 @@ void CaService::AddRSUContainerHighFrequency(CAMContainer::HighFrequencyContaine PCZ.protectedZoneLongitude = 50; PCZ.protectedZoneRadiusAvailable = false; PCZ.protectedZoneIDAvailable = false; - rsu.protectedCommunicationZonesRSU.list.push_back(PCZ); + rsu.protectedCommunicationZonesRSU.data[i]=PCZ; rsu.protectedCommunicationZonesRSU.ProtectedCommunicationZoneCount += 1; } } void CaService::AddLowFrequencyContainer(CAMContainer::LowFrequencyContainer_t &lfc) { + if (mVehicle == nullptr) { + return; + } + lfc.present = CAMContainer::LowFrequencyContainer_PR_basicVehicleContainerLowFrequency; CAMContainer::BasicVehicleContainerLowFrequency_t &bvc = lfc.basicVehicleContainerLowFrequency; @@ -736,12 +757,14 @@ void CaService::AddLowFrequencyContainer(CAMContainer::LowFrequencyContainer_t & bool CaService::CheckHeadingDelta(float DeltaSeconds) { - // if heading diff is more than 4degree - VehicleHeading = mVehicle->GetVehicleOrientation(); - double HeadingDelta = carla::geom::Math::ToDegrees(GetFVectorAngle(mLastCamHeading, VehicleHeading)); - if (HeadingDelta > 4.0) - { - return true; + if ( mVehicle != nullptr ) { + // if heading diff is more than 4degree + VehicleHeading = mVehicle->GetVehicleOrientation(); + double HeadingDelta = carla::geom::Math::ToDegrees(GetFVectorAngle(mLastCamHeading, VehicleHeading)); + if (HeadingDelta > 4.0) + { + return true; + } } return false; } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h index 1af1f09654a..15636e633b7 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/CaService.h @@ -21,7 +21,7 @@ class CaService { public: CaService(URandomEngine *random_engine); - void SetOwner(UWorld *world, AActor *Owner); + void SetActor(UWorld *world, AActor *Owner); void SetParams(const float GenCamMin, const float GenCamMax, const bool FixedRate); void SetVelDeviation(const float noise_vel_stddev_x); @@ -36,14 +36,14 @@ class CaService const float noise_alt_bias, const float noise_head_bias); bool Trigger(float DeltaSeconds); - CAM_t GetCamMessage(); - + CAM_t GetCamMessage()const; + bool CarlaActorInitialized()const { return mCarlaActor!=nullptr; } private: - AActor *mActorOwner; - FCarlaActor *mCarlaActor; - UCarlaEpisode *mCarlaEpisode; - UWorld *mWorld; - ACarlaWheeledVehicle *mVehicle; + AActor *mActorOwner{nullptr}; + FCarlaActor *mCarlaActor{nullptr}; + UCarlaEpisode *mCarlaEpisode{nullptr}; + UWorld *mWorld{nullptr}; + ACarlaWheeledVehicle *mVehicle{nullptr}; float mLastCamTimeStamp; float mLastLowCamTimeStamp; float mGenCamMin; @@ -70,12 +70,12 @@ class CaService bool CheckHeadingDelta(float DeltaSeconds); bool CheckPositionDelta(float DeltaSeconds); bool CheckSpeedDelta(float DeltaSeconds); - double GetFVectorAngle(const FVector &a, const FVector &b); + double GetFVectorAngle(const FVector &a, const FVector &b)const; void GenerateCamMessage(float DeltaTime); - ITSContainer::StationType_t GetStationType(); + ITSContainer::StationType_t GetStationType()const; - float GetHeading(); - long GetVehicleRole(); + float GetHeading()const; + long GetVehicleRole()const; /* Constant values for message*/ const long mProtocolVersion = 2; @@ -84,7 +84,7 @@ class CaService long mStationType; carla::geom::Vector3D ComputeAccelerometer(const float DeltaTime); - const carla::geom::Vector3D ComputeAccelerometerNoise(const FVector &Accelerometer); + const carla::geom::Vector3D ComputeAccelerometerNoise(const FVector &Accelerometer)const; /// Standard deviation for acceleration settings. FVector StdDevAccel; @@ -95,7 +95,7 @@ class CaService float PrevDeltaTime; // GNSS reference position and heading - FVector GetReferencePosition(); + FVector GetReferencePosition()const; carla::geom::GeoProjection CurrentGeoProjection; float LatitudeDeviation; float LongitudeDeviation; @@ -108,12 +108,12 @@ class CaService float HeadingBias; // Velocity - float ComputeSpeed(); + float ComputeSpeed()const; float VelocityDeviation; // Yaw rate - const float ComputeYawNoise(const FVector &Gyroscope); - float ComputeYawRate(); + const float ComputeYawNoise(const FVector &Gyroscope)const; + float ComputeYawRate()const; float YawrateDeviation; float YawrateBias; @@ -128,5 +128,5 @@ class CaService // random for noise URandomEngine *mRandomEngine; - ITSContainer::SpeedValue_t BuildSpeedValue(const float vel); + ITSContainer::SpeedValue_t BuildSpeedValue(const float vel)const; }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp index ed3b18b559d..59ed6e1ea48 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.cpp @@ -8,6 +8,8 @@ #include "Carla/Game/CarlaEpisode.h" #include "Carla/Util/RandomEngine.h" #include "Math/UnrealMathUtility.h" +#include "DrawDebugHelpers.h" +#include "Carla/Util/RandomEngine.h" #include "DrawDebugHelpers.h" @@ -19,13 +21,9 @@ double PathLossModel::Frequency_GHz = 5.9f; double PathLossModel::Frequency = 5.9f * std::pow(10, 9); double PathLossModel::lambda = PathLossModel::c_speedoflight / (5.9f * std::pow(10, 9)); -PathLossModel::PathLossModel(URandomEngine *random_engine) +PathLossModel::PathLossModel(URandomEngine *random_engine, AActor *Owner) { mRandomEngine = random_engine; -} - -void PathLossModel::SetOwner(AActor *Owner) -{ mActorOwner = Owner; } @@ -74,10 +72,6 @@ void PathLossModel::Simulate(const std::vector ActorList, UCarla FVector OtherActorLocation; mReceiveActorPowerList.clear(); float ReceivedPower = 0; - // Logic to get height of the vehicle - // TODO: make that thing use the actual attachment and transform of the sensor - - double tx_height_local = (mActorOwner->GetSimpleCollisionHalfHeight() * 2.0f) + 2.0; const FActorRegistry &Registry = mCarlaEpisode->GetActorRegistry(); @@ -90,20 +84,17 @@ void PathLossModel::Simulate(const std::vector ActorList, UCarla continue; } OtherActorLocation = actor_power_pair.first->GetTransform().GetLocation(); - double rx_height_local = (actor_power_pair.first->GetSimpleCollisionHalfHeight() * 2.0) + 2.0; // calculate relative ht and hr respecting slope and elevation // cm // if objects are on a slope, minimum Z height of both is the reference to calculate transmitter height double ref0 = std::min(CurrentActorLocation.Z, OtherActorLocation.Z); // cm - double ht = CurrentActorLocation.Z + tx_height_local - ref0; - double hr = OtherActorLocation.Z + rx_height_local - ref0; + double ht = CurrentActorLocation.Z - ref0; + double hr = OtherActorLocation.Z - ref0; // localize to common ref0 as ground FVector source_rel = CurrentActorLocation; - source_rel.Z += tx_height_local; FVector dest_rel = OtherActorLocation; - dest_rel.Z += rx_height_local; double Distance3d = FVector::Distance(source_rel, dest_rel) / 100.0f; // From cm to m // to meters @@ -119,9 +110,7 @@ void PathLossModel::Simulate(const std::vector ActorList, UCarla OtherActorLocation, Distance3d, ht, - tx_height_local, hr, - rx_height_local, ref0); if (ReceivedPower > -1.0 * std::numeric_limits::max()) { @@ -137,9 +126,7 @@ float PathLossModel::CalculateReceivedPower(AActor *OtherActor, const FVector Destination, const double Distance3d, const double ht, - const double ht_local, const double hr, - const double hr_local, const double reference_z) { // hr in m @@ -156,9 +143,7 @@ float PathLossModel::CalculateReceivedPower(AActor *OtherActor, HitResult.Reset(); FVector tx = Source; - tx.Z += ht_local; FVector rx = Destination; - rx.Z += hr_local; mWorld->LineTraceMultiByObjectType(HitResult, tx, rx, ObjectParams); // all losses diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h index 2e9fd6071a5..c2234aec002 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2X/PathLossModel.h @@ -35,8 +35,7 @@ enum EScenario class PathLossModel { public: - PathLossModel(URandomEngine *random_engine); - void SetOwner(AActor *Owner); + PathLossModel(URandomEngine *random_engine, AActor *Owner); void SetScenario(EScenario scenario); void Simulate(const std::vector ActorList, UCarlaEpisode *CarlaEpisode, UWorld *World); ActorPowerMap GetReceiveActorPowerList(); @@ -62,9 +61,7 @@ class PathLossModel const FVector Destination, const double Distance3d, const double ht, - const double ht_local, const double hr, - const double hr_local, const double reference_z); void EstimatePathStateAndVehicleObstacles(AActor *OtherActor, FVector Source, double TxHeight, double RxHeight, double reference_z, EPathState &state, std::vector &vehicle_obstacles); double MakeVehicleBlockageLoss(double TxHeight, double RxHeight, double obj_height, double obj_distance); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.cpp index d61537f3a18..1801031f88b 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.cpp @@ -15,7 +15,8 @@ #include "V2X/CaService.h" #include "V2XSensor.h" #include "V2X/PathLossModel.h" -std::list AV2XSensor::mV2XActorContainer; + + AV2XSensor::ActorV2XDataMap AV2XSensor::mActorV2XDataMap; AV2XSensor::AV2XSensor(const FObjectInitializer &ObjectInitializer) @@ -25,34 +26,24 @@ AV2XSensor::AV2XSensor(const FObjectInitializer &ObjectInitializer) RandomEngine = CreateDefaultSubobject(TEXT("RandomEngine")); // Init path loss model - PathLossModelObj = new PathLossModel(RandomEngine); + PathLossModelObj = new PathLossModel(RandomEngine, this); CaServiceObj = new CaService(RandomEngine); -} -void AV2XSensor::SetOwner(AActor *Owner) -{ - UE_LOG(LogCarla, Warning, TEXT("V2XSensor: called setowner with %p"), Owner); - if (GetOwner() != nullptr) - { - AV2XSensor::mV2XActorContainer.remove(GetOwner()); - UE_LOG(LogCarla, Warning, TEXT("V2XSensor: removed old owner %p"), GetOwner()); - } + // we can't intialize owner for RSUs here, because CALRA Actor not yet existing... have to check on the fly +} - Super::SetOwner(Owner); +void AV2XSensor::InitModel(AActor *NewOwner) { + UE_LOG(LogCarla, Warning, TEXT("V2XSensor::InitOwner() function called %p: CarlaActorInitialized %i"), NewOwner, CaServiceObj->CarlaActorInitialized()); + UWorld *world = GetWorld(); + CaServiceObj->SetActor(world, NewOwner); +} - // Store the actor into the static list if the actor details are not available - if (Owner != nullptr) - { - if (std::find(AV2XSensor::mV2XActorContainer.begin(), AV2XSensor::mV2XActorContainer.end(), Owner) == AV2XSensor::mV2XActorContainer.end()) - { - AV2XSensor::mV2XActorContainer.push_back(Owner); - UE_LOG(LogCarla, Warning, TEXT("V2XSensor: added owner, length now %d"), AV2XSensor::mV2XActorContainer.size()); - } - UWorld *world = GetWorld(); - CaServiceObj->SetOwner(world, Owner); - PathLossModelObj->SetOwner(Owner); +void AV2XSensor::SetOwner(AActor *NewOwner) +{ + UE_LOG(LogCarla, Warning, TEXT("V2XSensor: called setowner with %p (old: %p)"), NewOwner, GetOwner()); + Super::SetOwner(NewOwner); + InitModel(NewOwner); } -} FActorDefinition AV2XSensor::GetSensorDefinition() { @@ -104,25 +95,27 @@ void AV2XSensor::SetScenario(EScenario scenario) */ void AV2XSensor::PrePhysTick(float DeltaSeconds) { + if ( !CaServiceObj->CarlaActorInitialized() ) { + // ensure a CarlaActor to be the owner if no parent actor + InitModel(this); + } + Super::PrePhysTick(DeltaSeconds); // Clear the message created during the last sim cycle - if (GetOwner()) - { - AV2XSensor::mActorV2XDataMap.erase(GetOwner()); + AV2XSensor::mActorV2XDataMap.erase(this); - // Step 0: Create message to send, if triggering conditions fulfilled - // this needs to be done in pre phys tick to enable synchronous reception in all other v2x sensors - // Check whether the message is generated - if (CaServiceObj->Trigger(DeltaSeconds)) - { - // If message is generated store it - // make a pair of message and sending power - // if different v2x sensors send with different power, we need to store that - carla::sensor::data::CAMData cam_pw; - cam_pw.Message = CaServiceObj->GetCamMessage(); - cam_pw.Power = PathLossModelObj->GetTransmitPower(); - AV2XSensor::mActorV2XDataMap.insert({GetOwner(), cam_pw}); - } + // Step 0: Create message to send, if triggering conditions fulfilled + // this needs to be done in pre phys tick to enable synchronous reception in all other v2x sensors + // Check whether the message is generated + if (CaServiceObj->Trigger(DeltaSeconds)) + { + // If message is generated store it + // make a pair of message and sending power + // if different v2x sensors send with different power, we need to store that + carla::sensor::data::CAMData cam_pw; + cam_pw.Message = CaServiceObj->GetCamMessage(); + cam_pw.Power = PathLossModelObj->GetTransmitPower(); + AV2XSensor::mActorV2XDataMap.insert({this, cam_pw}); } } @@ -168,68 +161,51 @@ void AV2XSensor::SetYawrateDeviation(const float noise_yawrate_stddev, const flo void AV2XSensor::PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaTime) { TRACE_CPUPROFILER_EVENT_SCOPE(AV2XSensor::PostPhysTick); - if (GetOwner()) + // Step 1: Create an actor list which has messages to send targeting this v2x sensor instance + std::vector ActorPowerList; + for (const auto &pair : AV2XSensor::mActorV2XDataMap) { - // Step 1: Create an actor list which has messages to send targeting this v2x sensor instance - std::vector ActorPowerList; - for (const auto &pair : AV2XSensor::mActorV2XDataMap) + if (pair.first != this) { - if (pair.first != GetOwner()) - { - ActorPowerPair actor_power_pair; - actor_power_pair.first = pair.first; - // actor sending with transmit power - actor_power_pair.second = pair.second.Power; - ActorPowerList.push_back(actor_power_pair); - } + ActorPowerPair actor_power_pair; + actor_power_pair.first = pair.first; + // actor sending with transmit power + actor_power_pair.second = pair.second.Power; + ActorPowerList.push_back(actor_power_pair); } + } - // Step 2: Simulate the communication for the actors in actor list to current actor. - if (!ActorPowerList.empty()) - { - UCarlaEpisode *carla_episode = UCarlaStatics::GetCurrentEpisode(GetWorld()); - PathLossModelObj->Simulate(ActorPowerList, carla_episode, GetWorld()); - // Step 3: Get the list of actors who can send message to current actor, and the receive power of their messages. - ActorPowerMap actor_receivepower_map = PathLossModelObj->GetReceiveActorPowerList(); - // Step 4: Retrieve the messages of the actors that are received - - // get registry to retrieve carla actor IDs - const FActorRegistry &Registry = carla_episode->GetActorRegistry(); - - AV2XSensor::V2XDataList msg_received_power_list; - for (const auto &pair : actor_receivepower_map) - { - // Note: AActor* sender_actor = pair.first; - carla::sensor::data::CAMData send_msg_and_pw = AV2XSensor::mActorV2XDataMap.at(pair.first); - carla::sensor::data::CAMData received_msg_and_pw; - // sent CAM - received_msg_and_pw.Message = send_msg_and_pw.Message; - // receive power - received_msg_and_pw.Power = pair.second; - - msg_received_power_list.push_back(received_msg_and_pw); - } - - WriteMessageToV2XData(msg_received_power_list); - } - // Step 5: Send message + carla::sensor::data::CAMDataS msg_received_power_list; + // Step 2: Simulate the communication for the actors in actor list to current actor. + if (!ActorPowerList.empty()) + { + UCarlaEpisode *carla_episode = UCarlaStatics::GetCurrentEpisode(GetWorld()); + PathLossModelObj->Simulate(ActorPowerList, carla_episode, GetWorld()); + // Step 3: Get the list of actors who can send message to current actor, and the receive power of their messages. + ActorPowerMap actor_receivepower_map = PathLossModelObj->GetReceiveActorPowerList(); + // Step 4: Retrieve the messages of the actors that are received - if (mV2XData.GetMessageCount() > 0) + // get registry to retrieve carla actor IDs + const FActorRegistry &Registry = carla_episode->GetActorRegistry(); + + for (const auto &pair : actor_receivepower_map) { - auto DataStream = GetDataStream(*this); - DataStream.SerializeAndSend(*this, mV2XData, DataStream.PopBufferFromPool()); + // Note: AActor* sender_actor = pair.first; + carla::sensor::data::CAMData const &send_msg_and_pw = AV2XSensor::mActorV2XDataMap.at(pair.first); + carla::sensor::data::CAMData received_msg_and_pw; + // sent CAM + received_msg_and_pw.Message = send_msg_and_pw.Message; + // receive power + received_msg_and_pw.Power = pair.second; + + msg_received_power_list.WriteMessage(received_msg_and_pw); } - mV2XData.Reset(); } -} + // Step 5: Send message -/* - * Function the store the message into the structure so it can be sent to python client - */ -void AV2XSensor::WriteMessageToV2XData(const AV2XSensor::V2XDataList &msg_received_power_list) -{ - for (const auto &elem : msg_received_power_list) + if (msg_received_power_list.GetMessageCount() > 0) { - mV2XData.WriteMessage(elem); + auto DataStream = GetDataStream(*this); + DataStream.SerializeAndSend(*this, msg_received_power_list, DataStream.PopBufferFromPool()); } } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.h index 9ce46dd2ac6..31e63888989 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/V2XSensor.h @@ -22,10 +22,6 @@ class CARLA_API AV2XSensor : public ASensor { GENERATED_BODY() - using FV2XData = carla::sensor::data::CAMDataS; - using ActorV2XDataMap = std::map; - using V2XDataList = std::vector; - public: AV2XSensor(const FObjectInitializer &ObjectInitializer); @@ -64,14 +60,11 @@ class CARLA_API AV2XSensor : public ASensor void SetOwner(AActor *Owner) override; private: - static std::list mV2XActorContainer; CaService *CaServiceObj; PathLossModel *PathLossModelObj; + void InitModel(AActor *Owner); // store data + using ActorV2XDataMap = std::map; static ActorV2XDataMap mActorV2XDataMap; - FV2XData mV2XData; - - // write - void WriteMessageToV2XData(const V2XDataList &msg_received_power_list); }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/WorldObserver.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/WorldObserver.cpp index d88ad19a45d..afdb1550708 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/WorldObserver.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/WorldObserver.cpp @@ -38,7 +38,15 @@ static auto FWorldObserver_GetActorState(const FCarlaActor &View, const FActorRe auto Vehicle = Cast(View.GetActor()); if (Vehicle != nullptr) { - state.vehicle_data.control = carla::rpc::VehicleControl{Vehicle->GetVehicleControl()}; + if (Vehicle->IsAckermannControlActive()) { + state.vehicle_data.control_type = carla::rpc::VehicleControlType::AckermannControl; + state.vehicle_data.control_data.ackermann_control = carla::rpc::VehicleAckermannControl{Vehicle->GetVehicleAckermannControl()}; + } + else { + state.vehicle_data.control_type = carla::rpc::VehicleControlType::VehicleControl; + state.vehicle_data.control_data.vehicle_control = carla::rpc::VehicleControl{Vehicle->GetVehicleControl()}; + } + auto Controller = Cast(Vehicle->GetController()); if (Controller != nullptr) { @@ -174,7 +182,14 @@ static auto FWorldObserver_GetDormantActorState(const FCarlaActor &View, const F if (AType::Vehicle == View.GetActorType()) { const FVehicleData* ActorData = View.GetActorData(); - state.vehicle_data.control = carla::rpc::VehicleControl{ActorData->Control}; + if (ActorData->bAckermannControlActive) { + state.vehicle_data.control_type = carla::rpc::VehicleControlType::AckermannControl; + state.vehicle_data.control_data.ackermann_control = carla::rpc::VehicleAckermannControl{ActorData->AckermannControl}; + } + else { + state.vehicle_data.control_type = carla::rpc::VehicleControlType::VehicleControl; + state.vehicle_data.control_data.vehicle_control = carla::rpc::VehicleControl{ActorData->Control}; + } using TLS = carla::rpc::TrafficLightState; state.vehicle_data.traffic_light_state = TLS::Green; state.vehicle_data.speed_limit = ActorData->SpeedLimit; @@ -344,15 +359,17 @@ static carla::Buffer FWorldObserver_Serialize( } ActorTransform = View->GetActorGlobalTransform(); - ActorDynamicState info = { + ActorDynamicState info{ View->GetActorId(), View->GetActorState(), carla::geom::Transform(ActorTransform), + carla::geom::Quaternion(ActorTransform.GetRotation()), carla::geom::Vector3D(Velocity.X, Velocity.Y, Velocity.Z), AngularVelocity, Acceleration, State, }; + write_data(info); } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/WorldObserver.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/WorldObserver.h index a0695fdf77b..9c9d4ce0137 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/WorldObserver.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/WorldObserver.h @@ -44,6 +44,8 @@ class FWorldObserver return {}; } + /// Dummy. Required for compatibility with other sensors only. + AActor * GetAttachParentActor() const { return nullptr; } private: FDataMultiStream Stream; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp index 0de938fad1c..6dd8c1168c6 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp @@ -5,9 +5,11 @@ // For a copy, see . #include "Carla.h" +#include "rpc/this_session.h" #include "Carla/Server/CarlaServer.h" #include "Carla/Server/CarlaServerResponse.h" #include "Carla/Game/CarlaHUD.h" +#include "Carla/Server/ServerSynchronization.h" #include "Carla/Traffic/TrafficLightGroup.h" #include "EngineUtils.h" #include "Components/SkeletalMeshComponent.h" @@ -44,13 +46,12 @@ #include "Carla/Cosmos/Exporter/RoadMarkingExporter.h" #include +#include #include #include #include #include -#include #include -#include #include #include #include @@ -63,10 +64,8 @@ #include #include #include -#include #include #include -#include #include #include #include @@ -108,7 +107,7 @@ static std::vector MakeVectorFromTArray(const TArray &Array) // -- FCarlaServer::FPimpl ----------------------------------------------- // ============================================================================= -class FCarlaServer::FPimpl +class FCarlaServer::FPimpl: public carla::rpc::RpcServerInterface { public: @@ -121,6 +120,24 @@ class FCarlaServer::FPimpl SecondaryServer = std::make_shared(SecondaryPort); SecondaryServer->SetCallbacks(); BindActions(); + + auto const RegisterResponse = ServerSync.RegisterSynchronizationParticipant(SynchronizationClientId()); + if ( RegisterResponse ) { + ServerSynchronizationParticipantId = RegisterResponse.Get(); + UE_LOG( + LogCarlaServer, + Verbose, + TEXT("Server registered for sync (session_id=%s, sync_id=%d)"), + UTF8_TO_TCHAR(SynchronizationClientId().c_str()), + ServerSynchronizationParticipantId); + } + else { + UE_LOG( + LogCarlaServer, + Error, + TEXT("Server registered for sync (session_id=%s) failed)"), + UTF8_TO_TCHAR(SynchronizationClientId().c_str())); + } } std::shared_ptr GetSecondaryServer() { @@ -140,10 +157,125 @@ class FCarlaServer::FPimpl UCarlaEpisode *Episode = nullptr; - std::atomic_size_t TickCuesReceived { 0u }; + ServerSynchronization ServerSync; -private: + // not used in this delegated interface + std::shared_ptr GetDispatcher() override { + carla::throw_exception(std::runtime_error("Internal Error: FCarlaServer::FPimpl::GetDispatcher() should never have been called")); + return nullptr; + } + + + /** + * @brief episode related calls + * @{ + */ + carla::rpc::Response call_load_new_episode(const std::string &map_name, const bool reset_settings, carla::rpc::MapLayer map_layers) override; + carla::rpc::Response call_get_episode_settings() override; + carla::rpc::Response call_set_episode_settings(carla::rpc::EpisodeSettings const &settings) override; + /** + * @} + */ + + /** + * @brief map related calls + * @{ + */ + carla::rpc::Response> call_get_available_maps() override; + carla::rpc::Response call_get_map_data() override; + carla::rpc::Response call_get_map_info() override; + /** + * @} + */ + + /** + * @brief actor related calls + * @{ + */ + carla::rpc::Response > call_get_actor_definitions() override; + carla::rpc::Response call_spawn_actor(carla::rpc::ActorDescription Description, const carla::rpc::Transform &Transform) override; + carla::rpc::Response call_spawn_actor_with_parent(carla::rpc::ActorDescription Description, const carla::rpc::Transform &Transform, + carla::rpc::ActorId ParentId, carla::rpc::AttachmentType InAttachmentType, + const std::string &socket_name) override; + carla::rpc::Response call_destroy_actor(carla::rpc::ActorId ActorId) override; + carla::rpc::Response call_get_telemetry_data(carla::rpc::ActorId ActorId) override; + /** + * @} + */ + + /** + * @brief ros actor interaction calls + * @{ + */ + carla::rpc::Response call_enable_actor_for_ros(carla::rpc::ActorId actor_id) override; + carla::rpc::Response call_disable_actor_for_ros(carla::rpc::ActorId actor_id) override; + carla::rpc::Response call_is_actor_enabled_for_ros(carla::rpc::ActorId actor_id) override; + + /** + * @} + */ + + /** + * @brief synchronization calls + * @{ + */ + carla::rpc::Response call_tick( + carla::rpc::synchronization_client_id_type const &client_id, + carla::rpc::synchronization_participant_id_type const &participant_id) override; + carla::rpc::Response call_register_synchronization_participant( + carla::rpc::synchronization_client_id_type const &client_id, + carla::rpc::synchronization_participant_id_type const &participant_id_hint = carla::rpc::ALL_PARTICIPANTS) override; + carla::rpc::Response call_deregister_synchronization_participant( + carla::rpc::synchronization_client_id_type const &client_id, carla::rpc::synchronization_participant_id_type const &participant_id) override; + carla::rpc::Response call_update_synchronization_window( + carla::rpc::synchronization_client_id_type const &client_id, carla::rpc::synchronization_participant_id_type const &participant_id, + carla::rpc::synchronization_target_game_time const &target_game_time = carla::rpc::NO_SYNC_TARGET_GAME_TIME) override; + carla::rpc::Response > > call_get_synchronization_window_status() override; + /** + * @} + */ + + struct CheckHandleActorInSecondaryServerResult { + bool actor_exists; + bool handle_in_secondary_server; + FString actor_type_id; + carla::streaming::detail::stream_actor_id_type stream_actor_id; + }; + CheckHandleActorInSecondaryServerResult CheckHandleSensorInSecondaryServer(carla::streaming::detail::stream_id_type stream_id); + CheckHandleActorInSecondaryServerResult CheckHandleActorInSecondaryServer(carla::streaming::detail::actor_id_type actor_id); + CheckHandleActorInSecondaryServerResult CheckHandleActorInSecondaryServer(FCarlaActor* CarlaActor, + carla::streaming::detail::stream_actor_id_type stream_actor_id); + + void OnClientDisconnected(std::shared_ptr server_session); + void OnClientConnected(std::shared_ptr server_session); + bool IsNextGameTickAllowed(); + + void EnableSynchronousMode(); + void DisableSynchronousMode(); + void NotifyEndEpisode(); + + carla::rpc::synchronization_client_id_type SynchronizationClientId() const { return "CarlaServer"; } + carla::rpc::synchronization_participant_id_type TickParticipantId(::rpc::session_id_t RpcSessionId = ::rpc::this_session().id() ) { + carla::rpc::synchronization_participant_id_type SynchronizationParticipantId = ServerSynchronizationParticipantId; + auto TickParticipantIdIter = TickSynchronizationParticipantMap.find(RpcSessionId); + if ( TickParticipantIdIter!=TickSynchronizationParticipantMap.end()) { + SynchronizationParticipantId = TickParticipantIdIter->second; + } + return SynchronizationParticipantId; + } + double GetTickDeltaSeconds() { + double FixedDeltaSeconds = 1./20.; + if ((Episode != nullptr) && Episode->GetSettings().FixedDeltaSeconds.IsSet()) { + FixedDeltaSeconds = Episode->GetSettings().FixedDeltaSeconds.GetValue(); + } + return FixedDeltaSeconds; + } + + carla::rpc::synchronization_participant_id_type ServerSynchronizationParticipantId{0}; + std::map<::rpc::session_id_t, carla::rpc::synchronization_participant_id_type> TickSynchronizationParticipantMap; + +private: void BindActions(); }; @@ -232,6 +364,9 @@ void FCarlaServer::FPimpl::BindActions() namespace cr = carla::rpc; namespace cg = carla::geom; + Server.BindOnClientConnected(std::bind(&FCarlaServer::FPimpl::OnClientConnected, this, std::placeholders::_1)); + Server.BindOnClientDisconnected(std::bind(&FCarlaServer::FPimpl::OnClientDisconnected, this, std::placeholders::_1)); + /// Looks for a Traffic Manager running on port BIND_SYNC(is_traffic_manager_running) << [this] (uint16_t port) ->R { @@ -283,54 +418,27 @@ void FCarlaServer::FPimpl::BindActions() BIND_SYNC(tick_cue) << [this]() -> R { TRACE_CPUPROFILER_EVENT_SCOPE(TickCueReceived); - auto Current = FCarlaEngine::GetFrameCounter(); - (void)TickCuesReceived.fetch_add(1, std::memory_order_release); - return Current + 1; + UE_LOG( + LogCarlaServer, + Verbose, + TEXT("Tick received (session_id=%s, sync_id=%d, rpc_sid=%li)"), + UTF8_TO_TCHAR(SynchronizationClientId().c_str()), + TickParticipantId(), + ::rpc::this_session().id()); + return call_tick(SynchronizationClientId(), TickParticipantId()); }; // ~~ Load new episode ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ BIND_ASYNC(get_available_maps) << [this]() -> R> { - const auto MapNames = UCarlaStatics::GetAllMapNames(); - std::vector result; - result.reserve(MapNames.Num()); - for (const auto &MapName : MapNames) - { - if (MapName.Contains("/Sublevels/")) - continue; - if (MapName.Contains("/BaseMap/")) - continue; - if (MapName.Contains("/BaseLargeMap/")) - continue; - if (MapName.Contains("_Tile_")) - continue; - - result.emplace_back(cr::FromFString(MapName)); - } - return result; + return call_get_available_maps(); }; - BIND_SYNC(load_new_episode) << [this](const std::string &map_name, const bool reset_settings, cr::MapLayer MapLayers) -> R + BIND_SYNC(load_new_episode) << [this](const std::string &map_name, const bool reset_settings, cr::MapLayer map_layers) -> R { REQUIRE_CARLA_EPISODE(); - - UCarlaGameInstance* GameInstance = UCarlaStatics::GetGameInstance(Episode->GetWorld()); - if (!GameInstance) - { - RESPOND_ERROR("unable to find CARLA game instance"); - } - GameInstance->SetMapLayer(static_cast(MapLayers)); - - if(!Episode->LoadNewEpisode(cr::ToFString(map_name), reset_settings)) - { - FString Str(TEXT("Map '")); - Str += cr::ToFString(map_name); - Str += TEXT("' not found"); - RESPOND_ERROR_FSTRING(Str); - } - - return R::Success(); + return call_load_new_episode(map_name, reset_settings, map_layers); }; BIND_SYNC(load_map_layer) << [this](cr::MapLayer MapLayers) -> R @@ -591,20 +699,13 @@ void FCarlaServer::FPimpl::BindActions() BIND_SYNC(get_map_info) << [this]() -> R { REQUIRE_CARLA_EPISODE(); - ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld()); - const auto &SpawnPoints = Episode->GetRecommendedSpawnPoints(); - FString FullMapPath = GameMode->GetFullMapPath(); - FString MapDir = FullMapPath.RightChop(FullMapPath.Find("Content/", ESearchCase::CaseSensitive) + 8); - MapDir += "/" + Episode->GetMapName(); - return cr::MapInfo{ - cr::FromFString(MapDir), - MakeVectorFromTArray(SpawnPoints)}; + return call_get_map_info(); }; - BIND_SYNC(get_map_data) << [this]() -> R + BIND_SYNC(get_map_data) << [this]() -> R { REQUIRE_CARLA_EPISODE(); - return cr::FromLongFString(UOpenDrive::GetXODR(Episode->GetWorld())); + return call_get_map_data(); }; BIND_SYNC(get_navigation_mesh) << [this]() -> R> @@ -666,34 +767,20 @@ void FCarlaServer::FPimpl::BindActions() BIND_SYNC(get_episode_settings) << [this]() -> R { REQUIRE_CARLA_EPISODE(); - return cr::EpisodeSettings{Episode->GetSettings()}; + return call_get_episode_settings(); }; BIND_SYNC(set_episode_settings) << [this]( const cr::EpisodeSettings &settings) -> R { REQUIRE_CARLA_EPISODE(); - Episode->ApplySettings(settings); - StreamingServer.SetSynchronousMode(settings.synchronous_mode); - - ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld()); - if (!GameMode) - { - RESPOND_ERROR("unable to find CARLA game mode"); - } - ALargeMapManager* LargeMap = GameMode->GetLMManager(); - if (LargeMap) - { - LargeMap->ConsiderSpectatorAsEgo(settings.spectator_as_ego); - } - - return FCarlaEngine::GetFrameCounter(); + return call_set_episode_settings(settings); }; - BIND_SYNC(get_actor_definitions) << [this]() -> R> + BIND_SYNC(get_actor_definitions) << [this]() -> R> { REQUIRE_CARLA_EPISODE(); - return MakeVectorFromTArray(Episode->GetActorDefinitions()); + return call_get_actor_definitions(); }; BIND_SYNC(get_spectator) << [this]() -> R @@ -799,9 +886,9 @@ void FCarlaServer::FPimpl::BindActions() Weather->ApplyWeather(weather); return R::Success(); }; - + // -- IMUI Gravity --------------------------------------------------------- - + BIND_SYNC(get_imui_gravity) << [this]() -> R { REQUIRE_CARLA_EPISODE(); @@ -845,115 +932,28 @@ void FCarlaServer::FPimpl::BindActions() }; BIND_SYNC(spawn_actor) << [this]( - cr::ActorDescription Description, - const cr::Transform &Transform) -> R + carla::rpc::ActorDescription Description, + const carla::rpc::Transform &Transform) -> R { REQUIRE_CARLA_EPISODE(); - - auto Result = Episode->SpawnActorWithInfo(Transform, std::move(Description)); - - if (Result.Key != EActorSpawnResultStatus::Success) - { - UE_LOG(LogCarla, Error, TEXT("Actor not Spawned")); - RESPOND_ERROR_FSTRING(FActorSpawnResult::StatusToString(Result.Key)); - } - - ALargeMapManager* LargeMap = UCarlaStatics::GetLargeMapManager(Episode->GetWorld()); - if(LargeMap) - { - LargeMap->OnActorSpawned(*Result.Value); - } - - return Episode->SerializeActor(Result.Value); + return call_spawn_actor(Description, Transform); }; BIND_SYNC(spawn_actor_with_parent) << [this]( - cr::ActorDescription Description, - const cr::Transform &Transform, - cr::ActorId ParentId, - cr::AttachmentType InAttachmentType, - const std::string& socket_name) -> R + carla::rpc::ActorDescription Description, + const carla::rpc::Transform &Transform, + carla::rpc::ActorId ParentId, + carla::rpc::AttachmentType InAttachmentType, + const std::string& socket_name) -> R { REQUIRE_CARLA_EPISODE(); - - auto Result = Episode->SpawnActorWithInfo(Transform, std::move(Description)); - if (Result.Key != EActorSpawnResultStatus::Success) - { - RESPOND_ERROR_FSTRING(FActorSpawnResult::StatusToString(Result.Key)); - } - - FCarlaActor* CarlaActor = Episode->FindCarlaActor(Result.Value->GetActorId()); - if (!CarlaActor) - { - RESPOND_ERROR("internal error: actor could not be spawned"); - } - - FCarlaActor* ParentCarlaActor = Episode->FindCarlaActor(ParentId); - - if (!ParentCarlaActor) - { - RESPOND_ERROR("unable to attach actor: parent actor not found"); - } - - CarlaActor->SetParent(ParentId); - CarlaActor->SetAttachmentType(InAttachmentType); - ParentCarlaActor->AddChildren(CarlaActor->GetActorId()); - - #if defined(WITH_ROS2) - auto ROS2 = carla::ros2::ROS2::GetInstance(); - if (ROS2->IsEnabled()) - { - FCarlaActor* CurrentActor = ParentCarlaActor; - while(CurrentActor) - { - for (const auto &Attr : CurrentActor->GetActorInfo()->Description.Variations) - { - if (Attr.Key == "ros_name") - { - const std::string value = std::string(TCHAR_TO_UTF8(*Attr.Value.Value)); - ROS2->RegisterActorParent(static_cast(CarlaActor->GetActor()), static_cast(CurrentActor->GetActor())); - } - } - CurrentActor = Episode->FindCarlaActor(CurrentActor->GetParent()); - } - } - #endif - - // Only is possible to attach if the actor has been really spawned and - // is not in dormant state - if(!ParentCarlaActor->IsDormant()) - { - Episode->AttachActors( - CarlaActor->GetActor(), - ParentCarlaActor->GetActor(), - static_cast(InAttachmentType), - FString(socket_name.c_str())); - } - else - { - Episode->PutActorToSleep(CarlaActor->GetActorId()); - } - - return Episode->SerializeActor(CarlaActor); + return call_spawn_actor_with_parent(Description, Transform, ParentId, InAttachmentType, socket_name); }; - BIND_SYNC(destroy_actor) << [this](cr::ActorId ActorId) -> R + BIND_SYNC(destroy_actor) << [this](carla::rpc::ActorId ActorId) -> R { REQUIRE_CARLA_EPISODE(); - FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId); - if ( !CarlaActor ) - { - RESPOND_ERROR("unable to destroy actor: not found"); - } - UE_LOG(LogCarla, Log, TEXT("CarlaServer destroy_actor %d"), ActorId); - // We need to force the actor state change, since dormant actors - // will ignore the FCarlaActor destruction - CarlaActor->SetActorState(cr::ActorState::PendingKill); - if (!Episode->DestroyActor(ActorId)) - { - RESPOND_ERROR("internal error: unable to destroy actor"); - } - return true; + return call_destroy_actor(ActorId); }; BIND_SYNC(console_command) << [this](std::string cmd) -> R @@ -971,138 +971,50 @@ void FCarlaServer::FPimpl::BindActions() return GEngine->Exec(Episode->GetWorld(), UTF8_TO_TCHAR(cmd.c_str())); }; - BIND_SYNC(get_sensor_token) << [this](carla::streaming::detail::stream_id_type sensor_id) -> + BIND_SYNC(get_sensor_token) << [this](carla::streaming::detail::stream_id_type stream_id) -> R { REQUIRE_CARLA_EPISODE(); - bool ForceInPrimary = false; - - // check for the world observer (always in primary server) - if (sensor_id == 1) - { - ForceInPrimary = true; - } - - // collision sensor always in primary server in multi-gpu - FString Desc = Episode->GetActorDescriptionFromStream(sensor_id); - if (Desc == "" || Desc == "sensor.other.collision") - { - ForceInPrimary = true; - } - - if (SecondaryServer->HasClientsConnected() && !ForceInPrimary) + auto check_result = CheckHandleSensorInSecondaryServer(stream_id); + if ( check_result.handle_in_secondary_server ) { // multi-gpu - UE_LOG(LogCarla, Log, TEXT("Sensor %d '%s' created in secondary server"), sensor_id, *Desc); - return SecondaryServer->GetCommander().GetToken(sensor_id); + UE_LOG(LogCarla, Log, TEXT("Sensor %d '%s' created in secondary server"), stream_id, *check_result.actor_type_id); + return SecondaryServer->GetCommander().GetToken(stream_id); } else { // single-gpu - UE_LOG(LogCarla, Log, TEXT("Sensor %d '%s' created in primary server"), sensor_id, *Desc); - return StreamingServer.GetToken(sensor_id); + UE_LOG(LogCarla, Log, TEXT("Sensor %d '%s' created in primary server"), stream_id, *check_result.actor_type_id); + return StreamingServer.GetToken(stream_id); } }; - BIND_SYNC(enable_sensor_for_ros) << [this](carla::streaming::detail::stream_id_type sensor_id) -> + BIND_SYNC(enable_actor_for_ros) << [this](carla::rpc::ActorId ActorId) -> R { REQUIRE_CARLA_EPISODE(); - bool ForceInPrimary = false; - - // check for the world observer (always in primary server) - if (sensor_id == 1) - { - ForceInPrimary = true; - } - - // collision sensor always in primary server in multi-gpu - FString Desc = Episode->GetActorDescriptionFromStream(sensor_id); - if (Desc == "" || Desc == "sensor.other.collision") - { - ForceInPrimary = true; - } - - if (SecondaryServer->HasClientsConnected() && !ForceInPrimary) - { - // multi-gpu - SecondaryServer->GetCommander().EnableForROS(sensor_id); - } - else - { - // single-gpu - StreamingServer.EnableForROS(sensor_id); - } - return R::Success(); + return call_enable_actor_for_ros(ActorId); }; - BIND_SYNC(disable_sensor_for_ros) << [this](carla::streaming::detail::stream_id_type sensor_id) -> + BIND_SYNC(disable_actor_for_ros) << [this](carla::rpc::ActorId ActorId) -> R { REQUIRE_CARLA_EPISODE(); - bool ForceInPrimary = false; - - // check for the world observer (always in primary server) - if (sensor_id == 1) - { - ForceInPrimary = true; - } - - // collision sensor always in primary server in multi-gpu - FString Desc = Episode->GetActorDescriptionFromStream(sensor_id); - if (Desc == "" || Desc == "sensor.other.collision") - { - ForceInPrimary = true; - } - - if (SecondaryServer->HasClientsConnected() && !ForceInPrimary) - { - // multi-gpu - SecondaryServer->GetCommander().DisableForROS(sensor_id); - } - else - { - // single-gpu - StreamingServer.DisableForROS(sensor_id); - } - return R::Success(); + return call_disable_actor_for_ros(ActorId); }; -BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_id_type sensor_id) -> + BIND_SYNC(is_actor_enabled_for_ros) << [this](carla::rpc::ActorId ActorId) -> R { REQUIRE_CARLA_EPISODE(); - bool ForceInPrimary = false; - - // check for the world observer (always in primary server) - if (sensor_id == 1) - { - ForceInPrimary = true; - } - - // collision sensor always in primary server in multi-gpu - FString Desc = Episode->GetActorDescriptionFromStream(sensor_id); - if (Desc == "" || Desc == "sensor.other.collision") - { - ForceInPrimary = true; - } - - if (SecondaryServer->HasClientsConnected() && !ForceInPrimary) - { - // multi-gpu - return SecondaryServer->GetCommander().IsEnabledForROS(sensor_id); - } - else - { - // single-gpu - return StreamingServer.IsEnabledForROS(sensor_id); - } + return call_is_actor_enabled_for_ros(ActorId); }; - BIND_SYNC(send) << [this]( +BIND_SYNC(send) << [this]( cr::ActorId ActorId, - std::string message) -> R + cr::CustomV2XBytes Data) -> R { REQUIRE_CARLA_EPISODE(); FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId); @@ -1130,7 +1042,7 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ " Actor Id: " + FString::FromInt(ActorId)); } - Sensor->Send(cr::ToFString(message)); + Sensor->Send(Data); return R::Success(); }; @@ -1256,7 +1168,7 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ CarlaActor->SetWalkerState( Transform, cr::WalkerControl( - Transform.GetForwardVector(), Speed, false)); + Transform.GetForwardVector(), Speed, false, float(Episode->GetElapsedGameTime()))); if (Response != ECarlaServerResponse::Success) { return RespondError( @@ -1683,11 +1595,11 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ { FTransform WorldTransform = SkinnedMeshComponent->GetComponentTransform(); FTransform BoneTransform = SkinnedMeshComponent->GetBoneTransform(BoneIndex, WorldTransform); - BoneWorldTransforms.Add(BoneTransform); + BoneWorldTransforms.Add(BoneTransform); } } return MakeVectorFromTArray(BoneWorldTransforms); - } + } } }; @@ -1742,7 +1654,7 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ for (int32 BoneIndex = 0; BoneIndex < NumBones; ++BoneIndex) { FTransform BoneTransform = SkinnedMeshComponent->GetBoneTransform(BoneIndex, FTransform::Identity); - BoneRelativeTransforms.Add(BoneTransform); + BoneRelativeTransforms.Add(BoneTransform); } } return MakeVectorFromTArray(BoneRelativeTransforms); @@ -1771,8 +1683,8 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ { FString ComponentName = Cmp->GetName(); ComponentNames.push_back(TCHAR_TO_UTF8(*ComponentName)); - } - return ComponentNames; + } + return ComponentNames; } }; @@ -1791,13 +1703,13 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ else { USkinnedMeshComponent* SkinnedMeshComponent = CarlaActor->GetActor()->FindComponentByClass(); - if(!SkinnedMeshComponent) + if(!SkinnedMeshComponent) { return RespondError( "get_actor_bone_names", ECarlaServerResponse::ComponentNotFound, - " Component Name: SkinnedMeshComponent "); - } + " Component Name: SkinnedMeshComponent "); + } else { TArray BoneNames; @@ -1830,12 +1742,12 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ { TArray SocketWorldTransforms; TArray Components; - CarlaActor->GetActor()->GetComponents(Components); + CarlaActor->GetActor()->GetComponents(Components); for(UActorComponent* ActorComponent : Components) { if(USceneComponent* SceneComponent = Cast(ActorComponent)) { - const TArray& SocketNames = SceneComponent->GetAllSocketNames(); + const TArray& SocketNames = SceneComponent->GetAllSocketNames(); for (const FName& SocketName : SocketNames) { FTransform SocketTransform = SceneComponent->GetSocketTransform(SocketName); @@ -1843,7 +1755,7 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ } } } - return MakeVectorFromTArray(SocketWorldTransforms); + return MakeVectorFromTArray(SocketWorldTransforms); } }; @@ -1863,12 +1775,12 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ { TArray SocketRelativeTransforms; TArray Components; - CarlaActor->GetActor()->GetComponents(Components); + CarlaActor->GetActor()->GetComponents(Components); for(UActorComponent* ActorComponent : Components) { if(USceneComponent* SceneComponent = Cast(ActorComponent)) { - const TArray& SocketNames = SceneComponent->GetAllSocketNames(); + const TArray& SocketNames = SceneComponent->GetAllSocketNames(); for (const FName& SocketName : SocketNames) { FTransform SocketTransform = SceneComponent->GetSocketTransform(SocketName, ERelativeTransformSpace::RTS_Actor); @@ -1897,21 +1809,21 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ TArray SocketNames; std::vector StringSocketNames; TArray Components; - CarlaActor->GetActor()->GetComponents(Components); + CarlaActor->GetActor()->GetComponents(Components); for(UActorComponent* ActorComponent : Components) { if(USceneComponent* SceneComponent = Cast(ActorComponent)) { - SocketNames = SceneComponent->GetAllSocketNames(); + SocketNames = SceneComponent->GetAllSocketNames(); for (const FName& Name : SocketNames) { FString FSocketName = Name.ToString(); std::string StringSocketName = TCHAR_TO_UTF8(*FSocketName); StringSocketNames.push_back(StringSocketName); - } + } } } - return StringSocketNames; + return StringSocketNames; } }; @@ -2540,25 +2452,7 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ cr::ActorId ActorId) -> R { REQUIRE_CARLA_EPISODE(); - FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId); - if (!CarlaActor) - { - return RespondError( - "get_telemetry_data", - ECarlaServerResponse::ActorNotFound, - " Actor Id: " + FString::FromInt(ActorId)); - } - FVehicleTelemetryData TelemetryData; - ECarlaServerResponse Response = - CarlaActor->GetVehicleTelemetryData(TelemetryData); - if (Response != ECarlaServerResponse::Success) - { - return RespondError( - "get_telemetry_data", - Response, - " Actor Id: " + FString::FromInt(ActorId)); - } - return cr::VehicleTelemetryData(TelemetryData); + return call_get_telemetry_data(ActorId); }; BIND_SYNC(show_vehicle_debug_telemetry) << [this]( @@ -3430,6 +3324,431 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ } +carla::rpc::Response FCarlaServer::FPimpl::call_load_new_episode(const std::string &map_name, const bool reset_settings, carla::rpc::MapLayer map_layers) +{ + UCarlaGameInstance* GameInstance = UCarlaStatics::GetGameInstance(Episode->GetWorld()); + if (!GameInstance) + { + RESPOND_ERROR("unable to find CARLA game instance"); + } + GameInstance->SetMapLayer(static_cast(map_layers)); + + if(!Episode->LoadNewEpisode(carla::rpc::ToFString(map_name), reset_settings)) + { + FString Str(TEXT("Map '")); + Str += carla::rpc::ToFString(map_name); + Str += TEXT("' not found"); + RESPOND_ERROR_FSTRING(Str); + } + + return carla::rpc::Response::Success(); +} + +carla::rpc::Response FCarlaServer::FPimpl::call_get_episode_settings() +{ + return carla::rpc::EpisodeSettings{Episode->GetSettings()}; +} + +carla::rpc::Response FCarlaServer::FPimpl::call_set_episode_settings(carla::rpc::EpisodeSettings const &settings) +{ + Episode->ApplySettings(settings); + StreamingServer.SetSynchronousMode(settings.synchronous_mode); + + ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld()); + if (!GameMode) + { + RESPOND_ERROR("unable to find CARLA game mode"); + } + ALargeMapManager* LargeMap = GameMode->GetLMManager(); + if (LargeMap) + { + LargeMap->ConsiderSpectatorAsEgo(settings.spectator_as_ego); + } + + return FCarlaEngine::GetFrameCounter(); +} + +carla::rpc::Response> FCarlaServer::FPimpl::call_get_available_maps() { + const auto MapNames = UCarlaStatics::GetAllMapNames(); + std::vector result; + result.reserve(MapNames.Num()); + for (const auto &MapName : MapNames) + { + if (MapName.Contains("/Sublevels/")) + continue; + if (MapName.Contains("/BaseMap/")) + continue; + if (MapName.Contains("/BaseLargeMap/")) + continue; + if (MapName.Contains("_Tile_")) + continue; + + result.emplace_back(carla::rpc::FromFString(MapName)); + } + return result; +} + +carla::rpc::Response FCarlaServer::FPimpl::call_get_map_data() { + return carla::rpc::FromLongFString(UOpenDrive::GetXODR(Episode->GetWorld())); +}; + +carla::rpc::Response FCarlaServer::FPimpl::call_get_map_info() { + ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld()); + const auto &SpawnPoints = Episode->GetRecommendedSpawnPoints(); + FString FullMapPath = GameMode->GetFullMapPath(); + FString MapDir = FullMapPath.RightChop(FullMapPath.Find("Content/", ESearchCase::CaseSensitive) + 8); + MapDir += "/" + Episode->GetMapName(); + return carla::rpc::MapInfo{ + carla::rpc::FromFString(MapDir), + MakeVectorFromTArray(SpawnPoints)}; +}; + +carla::rpc::Response > FCarlaServer::FPimpl::call_get_actor_definitions() { + return MakeVectorFromTArray(Episode->GetActorDefinitions()); +} + +carla::rpc::Response FCarlaServer::FPimpl::call_spawn_actor(carla::rpc::ActorDescription Description, const carla::rpc::Transform &Transform) { + auto Result = Episode->SpawnActorWithInfo(Transform, std::move(Description)); + + if (Result.Key != EActorSpawnResultStatus::Success) + { + UE_LOG(LogCarla, Error, TEXT("Actor not Spawned")); + RESPOND_ERROR_FSTRING(FActorSpawnResult::StatusToString(Result.Key)); + } + + ALargeMapManager* LargeMap = UCarlaStatics::GetLargeMapManager(Episode->GetWorld()); + if(LargeMap) + { + LargeMap->OnActorSpawned(*Result.Value); + } + + return Episode->SerializeActor(Result.Value); +} + +carla::rpc::Response FCarlaServer::FPimpl::call_spawn_actor_with_parent( + carla::rpc::ActorDescription Description, + const carla::rpc::Transform &Transform, + carla::rpc::ActorId ParentId, + carla::rpc::AttachmentType InAttachmentType, + const std::string& socket_name) { + + auto Result = Episode->SpawnActorWithInfo(Transform, std::move(Description)); + if (Result.Key != EActorSpawnResultStatus::Success) + { + RESPOND_ERROR_FSTRING(FActorSpawnResult::StatusToString(Result.Key)); + } + + FCarlaActor* CarlaActor = Episode->FindCarlaActor(Result.Value->GetActorId()); + if (!CarlaActor) + { + RESPOND_ERROR("internal error: actor could not be spawned"); + } + + FCarlaActor* ParentCarlaActor = Episode->FindCarlaActor(ParentId); + + if (!ParentCarlaActor) + { + RESPOND_ERROR("unable to attach actor: parent actor not found"); + } + + CarlaActor->SetParent(ParentId); + CarlaActor->SetAttachmentType(InAttachmentType); + ParentCarlaActor->AddChildren(CarlaActor->GetActorId()); + + // Only is possible to attach if the actor has been really spawned and + // is not in dormant state + if(!ParentCarlaActor->IsDormant()) + { + Episode->AttachActors( + CarlaActor->GetActor(), + ParentCarlaActor->GetActor(), + static_cast(InAttachmentType), + FString(socket_name.c_str())); + } + else + { + Episode->PutActorToSleep(CarlaActor->GetActorId()); + } + + return Episode->SerializeActor(CarlaActor); +} + +carla::rpc::Response FCarlaServer::FPimpl::call_destroy_actor(carla::rpc::ActorId ActorId) { + FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId); + if ( !CarlaActor ) + { + RESPOND_ERROR("unable to destroy actor: not found"); + } + UE_LOG(LogCarla, Log, TEXT("CarlaServer destroy_actor %d"), ActorId); + // We need to force the actor state change, since dormant actors + // will ignore the FCarlaActor destruction + CarlaActor->SetActorState(carla::rpc::ActorState::PendingKill); + if (!Episode->DestroyActor(ActorId)) + { + RESPOND_ERROR("internal error: unable to destroy actor"); + } + return true; +} + +carla::rpc::Response FCarlaServer::FPimpl::call_enable_actor_for_ros(carla::rpc::ActorId ActorId) +{ + auto check_result = CheckHandleActorInSecondaryServer(ActorId); + if ( !check_result.actor_exists ) + { + RESPOND_ERROR("unable to enable actor for ROS: not found"); + } + else if ( check_result.handle_in_secondary_server ) + { + // multi-gpu + SecondaryServer->GetCommander().EnableForROS(check_result.stream_actor_id); + } + else + { + // single-gpu + StreamingServer.EnableForROS(check_result.stream_actor_id); + } + return carla::rpc::Response::Success(); +}; + +carla::rpc::Response FCarlaServer::FPimpl::call_disable_actor_for_ros(carla::rpc::ActorId ActorId) +{ + auto check_result = CheckHandleActorInSecondaryServer(ActorId); + if ( !check_result.actor_exists ) + { + RESPOND_ERROR("unable to disable actor for ROS: not found"); + } + else if ( check_result.handle_in_secondary_server ) + { + // multi-gpu + SecondaryServer->GetCommander().DisableForROS(check_result.stream_actor_id); + } + else + { + // single-gpu + StreamingServer.DisableForROS(check_result.stream_actor_id); + } + return carla::rpc::Response::Success(); +}; + +carla::rpc::Response FCarlaServer::FPimpl::call_is_actor_enabled_for_ros(carla::rpc::ActorId ActorId) +{ + auto check_result = CheckHandleActorInSecondaryServer(ActorId); + if ( !check_result.actor_exists ) + { + RESPOND_ERROR("unable to check if actor is enabled for ROS: not found"); + } + else if ( check_result.handle_in_secondary_server ) + { + // multi-gpu + return SecondaryServer->GetCommander().IsEnabledForROS(check_result.stream_actor_id); + } + else + { + // single-gpu + return StreamingServer.IsEnabledForROS(check_result.stream_actor_id); + } +}; + +carla::rpc::Response FCarlaServer::FPimpl::call_get_telemetry_data(carla::rpc::ActorId ActorId) +{ + FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId); + if (!CarlaActor) + { + return RespondError( + "get_telemetry_data", + ECarlaServerResponse::ActorNotFound, + " Actor Id: " + FString::FromInt(ActorId)); + } + FVehicleTelemetryData TelemetryData; + ECarlaServerResponse Response = + CarlaActor->GetVehicleTelemetryData(TelemetryData); + if (Response != ECarlaServerResponse::Success) + { + return RespondError( + "get_telemetry_data", + Response, + " Actor Id: " + FString::FromInt(ActorId)); + } + return carla::rpc::VehicleTelemetryData(TelemetryData); +} + +carla::rpc::Response FCarlaServer::FPimpl::call_tick( + carla::rpc::synchronization_client_id_type const &client_id, + carla::rpc::synchronization_participant_id_type const&participant_id) +{ + REQUIRE_CARLA_EPISODE(); + auto Current = FCarlaEngine::GetFrameCounter(); + auto const TargetGameTime = Episode->GetElapsedGameTime() + GetTickDeltaSeconds(); + (void) call_update_synchronization_window(client_id, participant_id, TargetGameTime); + return Current + 1; +} + +carla::rpc::Response FCarlaServer::FPimpl::call_register_synchronization_participant( + carla::rpc::synchronization_client_id_type const &client_id, + carla::rpc::synchronization_participant_id_type const&participant_id_hint) +{ + return ServerSync.RegisterSynchronizationParticipant(client_id, participant_id_hint); +} + +carla::rpc::Response FCarlaServer::FPimpl::call_deregister_synchronization_participant( + carla::rpc::synchronization_client_id_type const &client_id, + carla::rpc::synchronization_participant_id_type const &participant_id) +{ + return ServerSync.DeregisterSynchronizationParticipant(client_id, participant_id); +} + +carla::rpc::Response FCarlaServer::FPimpl::call_update_synchronization_window( + carla::rpc::synchronization_client_id_type const &client_id, + carla::rpc::synchronization_participant_id_type const&participant_id, + carla::rpc::synchronization_target_game_time const &target_game_time) +{ + return ServerSync.UpdateSynchronizationWindow(client_id, participant_id, target_game_time); +} + +carla::rpc::Response > > FCarlaServer::FPimpl::call_get_synchronization_window_status() { + return ServerSync.GetSynchronizationWindowParticipantStates(); +} + +FCarlaServer::FPimpl::CheckHandleActorInSecondaryServerResult FCarlaServer::FPimpl::CheckHandleSensorInSecondaryServer(carla::streaming::detail::stream_id_type stream_id) { + FCarlaActor* CarlaActor = Episode->FindCarlaActorByStreamId(stream_id); + if ( CarlaActor == nullptr ) + { + return {/*.actor_exists = */false, + /*.handle_in_secondary_server = */false, + /*.actor_type_id = */"", + /*.stream_actor_id = */{stream_id, 0}}; + + } + return CheckHandleActorInSecondaryServer(CarlaActor, {stream_id, CarlaActor->GetActorId()}); +} + +FCarlaServer::FPimpl::CheckHandleActorInSecondaryServerResult FCarlaServer::FPimpl::CheckHandleActorInSecondaryServer(carla::streaming::detail::actor_id_type actor_id) { + FCarlaActor* CarlaActor = Episode->FindCarlaActor(actor_id); + // the world observer is responsible for streaming non-sensor actors + carla::streaming::detail::stream_id_type stream_id = 1; + + if (CarlaActor == nullptr) { + return {/*.actor_exists = */false, + /*.handle_in_secondary_server = */false, + /*.actor_type_id = */"", + /*.stream_actor_id = */{stream_id, actor_id}}; + } + + auto *Sensor = Cast(CarlaActor->GetActor()); + if ( Sensor != nullptr ) + { + stream_id = carla::streaming::detail::token_type(Sensor->GetToken()).get_stream_id(); + } + return CheckHandleActorInSecondaryServer(CarlaActor, {stream_id, actor_id}); +} + + + +FCarlaServer::FPimpl::CheckHandleActorInSecondaryServerResult FCarlaServer::FPimpl::CheckHandleActorInSecondaryServer(FCarlaActor* CarlaActor, + carla::streaming::detail::stream_actor_id_type stream_actor_id) { + + CheckHandleActorInSecondaryServerResult result = {/*.actor_exists = */true, + /*.handle_in_secondary_server = */false, + /*.actor_type_id = */CarlaActor->GetActorInfo()->Description.Id, + /*.stream_actor_id = */stream_actor_id}; + + // check for the world observer (always in primary server) + if (stream_actor_id.stream_id == 1 || + // collision sensor always in primary server + (result.actor_type_id == "sensor.other.collision") || + // sensor only in secondary if clients are connected + !SecondaryServer->HasClientsConnected() ) + { + result.handle_in_secondary_server = false; + } + else + { + result.handle_in_secondary_server = true; + } + + return result; +} + +void FCarlaServer::FPimpl::OnClientConnected(std::shared_ptr server_session) { + auto const rpc_sid = reinterpret_cast<::rpc::session_id_t>(server_session.get()); + auto const RegisterResponse = ServerSync.RegisterSynchronizationParticipant(SynchronizationClientId()); + if ( RegisterResponse ) { + TickSynchronizationParticipantMap.insert({rpc_sid, RegisterResponse.Get()}); + UE_LOG( + LogCarlaServer, + Verbose, + TEXT("Client connected (session_id=%s, sync_id=%d, rpc_sid=%li)"), + UTF8_TO_TCHAR(SynchronizationClientId().c_str()), + RegisterResponse.Get(), + rpc_sid); + } + else { + UE_LOG( + LogCarlaServer, + Error, + TEXT("Client connected (session_id=%s, rpc_sid=%li) registering for sync failed."), + UTF8_TO_TCHAR(SynchronizationClientId().c_str()), + rpc_sid); + } +} + +void FCarlaServer::FPimpl::OnClientDisconnected(std::shared_ptr server_session) { + auto const rpc_sid = reinterpret_cast<::rpc::session_id_t>(server_session.get()); + UE_LOG( + LogCarlaServer, + Verbose, + TEXT("Client disconnected (session_id=%s, sync_id=%d, rpc_sid=%li)"), + UTF8_TO_TCHAR(SynchronizationClientId().c_str()), + TickParticipantId(), + rpc_sid); + ServerSync.DeregisterSynchronizationParticipant(SynchronizationClientId(), TickParticipantId(rpc_sid)); + TickSynchronizationParticipantMap.erase(rpc_sid); + // TODO: ::rpc::this_session().id() is returning always 0 within the bound callbacks (which is not what is expected) + // So, we don't know which client enabled or disabled sync mode... + // Theoretically that client would have been identified correctly within it's enable/disable/tick call(s) and as it's data is dropped on Deregistering above + // all would work fine. But rpclib is not behaving as expected! + // Therefore, we disable synchronous mode completely for now to preserve from blocking + ServerSync.DisableSynchronousMode(SynchronizationClientId(), carla::rpc::ALL_PARTICIPANTS); +} + +bool FCarlaServer::FPimpl::IsNextGameTickAllowed() { + if (Episode == nullptr) { + return false; + } + auto const ElapsedGameTime = Episode->GetElapsedGameTime(); + auto TargetGameTime = ServerSync.GetTargetSynchronizationTime(ElapsedGameTime , GetTickDeltaSeconds()); + return TargetGameTime > ElapsedGameTime; +} + +void FCarlaServer::FPimpl::EnableSynchronousMode() { + UE_LOG( + LogCarlaServer, + Verbose, + TEXT("EnableSynchronousMode (session_id=%s, sync_id=%d, rpc_sid=%li)"), + UTF8_TO_TCHAR(SynchronizationClientId().c_str()), + TickParticipantId(), + ::rpc::this_session().id()); + ServerSync.EnableSynchronousMode(SynchronizationClientId(), TickParticipantId()); +} + +void FCarlaServer::FPimpl::DisableSynchronousMode() { + UE_LOG( + LogCarlaServer, + Verbose, + TEXT("DisableSynchronousMode (session_id=%s, sync_id=%d, rpc_sid=%li)"), + UTF8_TO_TCHAR(SynchronizationClientId().c_str()), + TickParticipantId(), + ::rpc::this_session().id()); + ServerSync.DisableSynchronousMode(SynchronizationClientId(), TickParticipantId()); +} + +void FCarlaServer::FPimpl::NotifyEndEpisode() +{ + TickSynchronizationParticipantMap.clear(); + ServerSync.DisconnectClient(SynchronizationClientId()); + Episode = nullptr; +} + // ============================================================================= // -- Undef helper macros ------------------------------------------------------ // ============================================================================= @@ -3441,6 +3760,7 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_ #undef RESPOND_ERROR #undef CARLA_ENSURE_GAME_THREAD + // ============================================================================= // -- FCarlaServer ------------------------------------------------------- // ============================================================================= @@ -3477,7 +3797,7 @@ void FCarlaServer::NotifyBeginEpisode(UCarlaEpisode &Episode) void FCarlaServer::NotifyEndEpisode() { check(Pimpl != nullptr); - Pimpl->Episode = nullptr; + Pimpl->NotifyEndEpisode(); } void FCarlaServer::AsyncRun(uint32 NumberOfWorkerThreads) @@ -3518,18 +3838,30 @@ void FCarlaServer::RunSome(uint32 Milliseconds) Pimpl->Server.SyncRunFor(carla::time_duration::milliseconds(Milliseconds)); } +void FCarlaServer::EnableSynchronousMode() { + Pimpl->EnableSynchronousMode(); +} + +void FCarlaServer::DisableSynchronousMode() { + Pimpl->DisableSynchronousMode(); +} + +bool FCarlaServer::IsSynchronousModeActive() { + return Pimpl->ServerSync.IsSynchronousModeActive(); +} + +void FCarlaServer::SetROS2TopicVisibilityDefaultEnabled(bool _topic_visibility_default_enabled) { + Pimpl->StreamingServer.SetROS2TopicVisibilityDefaultEnabled(_topic_visibility_default_enabled); +} + void FCarlaServer::Tick() { - (void)Pimpl->TickCuesReceived.fetch_add(1, std::memory_order_release); + (void)Pimpl->call_tick(Pimpl->SynchronizationClientId(), Pimpl->ServerSynchronizationParticipantId); } bool FCarlaServer::TickCueReceived() { - auto k = Pimpl->TickCuesReceived.fetch_sub(1, std::memory_order_acquire); - bool flag = (k > 0); - if (!flag) - (void)Pimpl->TickCuesReceived.fetch_add(1, std::memory_order_release); - return flag; + return Pimpl->IsNextGameTickAllowed(); } void FCarlaServer::Stop() @@ -3556,3 +3888,112 @@ carla::streaming::Server &FCarlaServer::GetStreamingServer() { return Pimpl->StreamingServer; } + +carla::rpc::Response FCarlaServer::call_load_new_episode(const std::string &map_name, const bool reset_settings, carla::rpc::MapLayer map_layers) +{ + return Pimpl->call_load_new_episode(map_name, reset_settings, map_layers); +} + +carla::rpc::Response FCarlaServer::call_get_episode_settings() +{ + return Pimpl->call_get_episode_settings(); +} + +carla::rpc::Response FCarlaServer::call_set_episode_settings(carla::rpc::EpisodeSettings const &settings) +{ + return Pimpl->call_set_episode_settings(settings); +} + +carla::rpc::Response> FCarlaServer::call_get_available_maps() +{ + return Pimpl->call_get_available_maps(); +} + +carla::rpc::Response FCarlaServer::call_get_map_data() +{ + return Pimpl->call_get_map_data(); +} + +carla::rpc::Response FCarlaServer::call_get_map_info() +{ + return Pimpl->call_get_map_info(); +} + +carla::rpc::Response > FCarlaServer::call_get_actor_definitions() +{ + return Pimpl->call_get_actor_definitions(); +} + +carla::rpc::Response FCarlaServer::call_spawn_actor(carla::rpc::ActorDescription Description, const carla::rpc::Transform &Transform) +{ + return Pimpl->call_spawn_actor(Description, Transform); +} + +carla::rpc::Response FCarlaServer::call_spawn_actor_with_parent( + carla::rpc::ActorDescription Description, + const carla::rpc::Transform &Transform, + carla::rpc::ActorId ParentId, + carla::rpc::AttachmentType InAttachmentType, + const std::string& socket_name) +{ + return Pimpl->call_spawn_actor_with_parent(Description, Transform, ParentId, InAttachmentType, socket_name); +} + +carla::rpc::Response FCarlaServer::call_destroy_actor(carla::rpc::ActorId ActorId) +{ + return Pimpl->call_destroy_actor(ActorId); +} + +carla::rpc::Response FCarlaServer::call_enable_actor_for_ros(carla::rpc::ActorId ActorId) +{ + return Pimpl->call_enable_actor_for_ros(ActorId); +} + +carla::rpc::Response FCarlaServer::call_disable_actor_for_ros(carla::rpc::ActorId ActorId) +{ + return Pimpl->call_disable_actor_for_ros(ActorId); +} + +carla::rpc::Response FCarlaServer::call_is_actor_enabled_for_ros(carla::rpc::ActorId ActorId) +{ + return Pimpl->call_is_actor_enabled_for_ros(ActorId); +} + +carla::rpc::Response FCarlaServer::call_get_telemetry_data(carla::rpc::ActorId ActorId) +{ + return Pimpl->call_get_telemetry_data(ActorId); +} + +carla::rpc::Response FCarlaServer::call_tick( + carla::rpc::synchronization_client_id_type const &client_id, + carla::rpc::synchronization_participant_id_type const&synchronization_participant) +{ + return Pimpl->call_tick(client_id, synchronization_participant); +} + +carla::rpc::Response FCarlaServer::call_register_synchronization_participant( + carla::rpc::synchronization_client_id_type const &client_id, + carla::rpc::synchronization_participant_id_type const &participant_id_hint) +{ + return Pimpl->call_register_synchronization_participant(client_id, participant_id_hint); +} + +carla::rpc::Response FCarlaServer::call_deregister_synchronization_participant( + carla::rpc::synchronization_client_id_type const &client_id, + carla::rpc::synchronization_participant_id_type const&synchronization_participant) +{ + return Pimpl->call_deregister_synchronization_participant(client_id, synchronization_participant); +} + +carla::rpc::Response FCarlaServer::call_update_synchronization_window( + carla::rpc::synchronization_client_id_type const &client_id, + carla::rpc::synchronization_participant_id_type const&synchronization_participant, + carla::rpc::synchronization_target_game_time const &target_game_time) +{ + return Pimpl->call_update_synchronization_window(client_id, synchronization_participant, target_game_time); +} + +carla::rpc::Response > > FCarlaServer::call_get_synchronization_window_status() { + return Pimpl->call_get_synchronization_window_status(); +} + diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.h index 340c1dcb716..0b772b71cdd 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.h @@ -14,11 +14,17 @@ #include #include #include +#include +#include +#include +#include +#include +#include #include class UCarlaEpisode; -class FCarlaServer +class FCarlaServer: public carla::rpc::RpcServerInterface { public: @@ -36,6 +42,12 @@ class FCarlaServer void RunSome(uint32 Milliseconds); + void EnableSynchronousMode(); + void DisableSynchronousMode(); + bool IsSynchronousModeActive(); + + void SetROS2TopicVisibilityDefaultEnabled(bool _topic_visibility_default_enabled); + void Tick(); bool TickCueReceived(); @@ -48,6 +60,82 @@ class FCarlaServer carla::streaming::Server &GetStreamingServer(); + /** + * Reimplemented from ROS2ServerInterfase + */ + std::shared_ptr GetDispatcher() override { + return GetStreamingServer().GetDispatcher(); + } + + + + /** + * @brief episode related calls + * @{ + */ + carla::rpc::Response call_load_new_episode(const std::string &map_name, const bool reset_settings, carla::rpc::MapLayer map_layers) override; + carla::rpc::Response call_get_episode_settings() override; + carla::rpc::Response call_set_episode_settings(carla::rpc::EpisodeSettings const &settings) override; + /** + * @} + */ + + /** + * @brief map related calls + * @{ + */ + carla::rpc::Response> call_get_available_maps() override; + carla::rpc::Response call_get_map_data() override; + carla::rpc::Response call_get_map_info() override; + /** + * @} + */ + + /** + * @brief actor related calls + * @{ + */ + carla::rpc::Response > call_get_actor_definitions() override; + carla::rpc::Response call_spawn_actor(carla::rpc::ActorDescription Description, const carla::rpc::Transform &Transform) override; + carla::rpc::Response call_spawn_actor_with_parent(carla::rpc::ActorDescription Description, const carla::rpc::Transform &Transform, + carla::rpc::ActorId ParentId, carla::rpc::AttachmentType InAttachmentType, + const std::string &socket_name) override; + carla::rpc::Response call_destroy_actor(carla::rpc::ActorId ActorId) override; + carla::rpc::Response call_get_telemetry_data(carla::rpc::ActorId ActorId) override; + /** + * @} + */ + + /** + * @brief ros actor interaction calls + * @{ + */ + carla::rpc::Response call_enable_actor_for_ros(carla::rpc::ActorId actor_id) override; + carla::rpc::Response call_disable_actor_for_ros(carla::rpc::ActorId actor_id) override; + carla::rpc::Response call_is_actor_enabled_for_ros(carla::rpc::ActorId actor_id) override; + /** + * @} + */ + + /** + * @brief synchronization calls + * @{ + */ + carla::rpc::Response call_tick( + carla::rpc::synchronization_client_id_type const &client_id = carla::rpc::ALL_CLIENTS, + carla::rpc::synchronization_participant_id_type const &participant_id = carla::rpc::ALL_PARTICIPANTS) override; + carla::rpc::Response call_register_synchronization_participant( + carla::rpc::synchronization_client_id_type const &client_id, + carla::rpc::synchronization_participant_id_type const &participant_id_hint = carla::rpc::ALL_PARTICIPANTS) override; + carla::rpc::Response call_deregister_synchronization_participant( + carla::rpc::synchronization_client_id_type const &client_id, carla::rpc::synchronization_participant_id_type const &participant_id) override; + carla::rpc::Response call_update_synchronization_window( + carla::rpc::synchronization_client_id_type const &client_id, carla::rpc::synchronization_participant_id_type const &participant_id, + carla::rpc::synchronization_target_game_time const &target_game_time = carla::rpc::NO_SYNC_TARGET_GAME_TIME) override; + carla::rpc::Response > > call_get_synchronization_window_status() override; + /** + * @} + */ private: class FPimpl; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/ServerSynchronization.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/ServerSynchronization.h new file mode 100644 index 00000000000..568902c384c --- /dev/null +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/ServerSynchronization.h @@ -0,0 +1,244 @@ +// Copyright (c) 2024 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include +#include +#include "carla/rpc/ServerSynchronizationTypes.h" +#include "carla/rpc/Response.h" +#include "carla/Logging.h" +#include "Carla/Game/CarlaEngine.h" + +/// The interface to the CARLA server required from TCP and ROS2 client side. +/// The parts only required from TPC client side are handled by lambdas directly. +class ServerSynchronization { +public: + ServerSynchronization() = default; + virtual ~ServerSynchronization() = default; + + + /** @brief Register a synchronization participant + * + * After the first synchronization participant is registered, the server runs in synchronous mode. + */ + carla::rpc::Response RegisterSynchronizationParticipant( + carla::rpc::synchronization_client_id_type const &ClientId, + carla::rpc::synchronization_participant_id_type const &ParticipantIdHint = carla::rpc::ALL_PARTICIPANTS) { + + std::lock_guard SyncLock(SynchronizationMutex); + + UE_LOG(LogCarla, Verbose, TEXT("ServerSynchronization::RegisterSynchronizationParticipant[%s:%u] hint"), UTF8_TO_TCHAR(ClientId.c_str()), ParticipantIdHint); + auto MaxIdIter = ParticipantIdMaxMap.find(ClientId); + if ( MaxIdIter==ParticipantIdMaxMap.end()) { + auto InsertResult = ParticipantIdMaxMap.insert( {ClientId, carla::rpc::ALL_PARTICIPANTS}); + MaxIdIter = InsertResult.first; + } + auto ParticipantId = ParticipantIdHint; + if ( ParticipantId==carla::rpc::ALL_PARTICIPANTS ) { + ParticipantId = ++(MaxIdIter->second); + } + + auto InsertResultIter = SynchronizationWindowMap.insert( { ClientId, {ParticipantId, carla::rpc::NO_SYNC_TARGET_GAME_TIME}}); + if ( InsertResultIter == SynchronizationWindowMap.end() ) { + // collision + UE_LOG(LogCarla, Error, TEXT("ServerSynchronization::RegisterSynchronizationParticipant[%s:%u] failed unexpectedly because of id clash"), UTF8_TO_TCHAR(ClientId.c_str()), ParticipantId); + LogSynchronizationMap("Register failed"); + return carla::rpc::ResponseError("ServerSynchronization::RegisterSynchronizationParticipant failed unexpectedly because of id clash\n"); + } + if (ParticipantId > MaxIdIter->second) { + MaxIdIter->second = ParticipantId; + } + UE_LOG(LogCarla, Verbose, TEXT("ServerSynchronization::RegisterSynchronizationParticipant[%s:%u]"), UTF8_TO_TCHAR(ClientId.c_str()), ParticipantId); + LogSynchronizationMap("Register end"); + SyncStateChanged=true; + return ParticipantId; + } + + bool DeregisterSynchronizationParticipant(carla::rpc::synchronization_client_id_type const &ClientId, + carla::rpc::synchronization_participant_id_type const &ParticipantId) { + + std::lock_guard SyncLock(SynchronizationMutex); + UE_LOG(LogCarla, Verbose, TEXT("ServerSynchronization::DeregisterSynchronizationParticipant[%s:%u]"), UTF8_TO_TCHAR(ClientId.c_str()), ParticipantId); + LogSynchronizationMap("Deregister start"); + auto const SynchronizationParticipantEqualRange = SynchronizationWindowMap.equal_range(ClientId); + for (auto SynchronizationWindowIter=SynchronizationParticipantEqualRange.first; + SynchronizationWindowIter != SynchronizationParticipantEqualRange.second; + /* no iterator update here to support erase */) { + if (SynchronizationWindowIter->second.ParticipantId == ParticipantId ) { + SynchronizationWindowIter = SynchronizationWindowMap.erase(SynchronizationWindowIter); + } + else { + SynchronizationWindowIter++; + } + } + LogSynchronizationMap("Deregister end"); + SyncStateChanged=true; + return true; + } + + void DisconnectClient(carla::rpc::synchronization_client_id_type const &ClientId) { + + std::lock_guard SyncLock(SynchronizationMutex); + + LogSynchronizationMap("Disconnect client start"); + auto ErasedEntries = SynchronizationWindowMap.erase(ClientId); + if ( ErasedEntries > 0u ) { + UE_LOG(LogCarla, Verbose, TEXT("ServerSynchronization::DisconnectClient[%s:ALL]"), UTF8_TO_TCHAR(ClientId.c_str())); + } + else { + UE_LOG(LogCarla, Warning, TEXT("ServerSynchronization::DisconnectClient[%s:ALL] client id not found"), UTF8_TO_TCHAR(ClientId.c_str())); + LogSynchronizationMap("Disconnect client not found"); + } + SyncStateChanged=true; + LogSynchronizationMap("Disconnect client end"); + } + + void EnableSynchronousMode(carla::rpc::synchronization_client_id_type const &ClientId, + carla::rpc::synchronization_participant_id_type const &ParticipantId = carla::rpc::ALL_PARTICIPANTS) { + + std::lock_guard SyncLock(SynchronizationMutex); + + for(auto &SynchronizationWindow: SynchronizationWindowMap) { + if ( (ClientId == SynchronizationWindow.first) && + (( ParticipantId == carla::rpc::ALL_PARTICIPANTS ) || ( SynchronizationWindow.second.ParticipantId == ParticipantId )) && + (SynchronizationWindow.second.TargetGameTime <= carla::rpc::NO_SYNC_TARGET_GAME_TIME)) { + SynchronizationWindow.second.TargetGameTime = carla::rpc::BLOCKING_TARGET_GAME_TIME; + SyncStateChanged=true; + } + } + UE_LOG(LogCarla, Verbose, TEXT("ServerSynchronization::EnableSynchronousMode[%s:%d]"), UTF8_TO_TCHAR(ClientId.c_str()), ParticipantId); + } + + void DisableSynchronousMode(carla::rpc::synchronization_client_id_type const &ClientId, + carla::rpc::synchronization_participant_id_type const &ParticipantId = carla::rpc::ALL_PARTICIPANTS) { + + std::lock_guard SyncLock(SynchronizationMutex); + + for(auto &SynchronizationWindow: SynchronizationWindowMap) { + if ( (ClientId == SynchronizationWindow.first) && + (( ParticipantId == carla::rpc::ALL_PARTICIPANTS ) || ( SynchronizationWindow.second.ParticipantId == ParticipantId )) && + (SynchronizationWindow.second.TargetGameTime > carla::rpc::NO_SYNC_TARGET_GAME_TIME)) { + SynchronizationWindow.second.TargetGameTime = carla::rpc::NO_SYNC_TARGET_GAME_TIME; + SyncStateChanged=true; + } + } + UE_LOG(LogCarla, Verbose, TEXT("ServerSynchronization::DisableSynchronousMode[%s:%d]"), UTF8_TO_TCHAR(ClientId.c_str()), ParticipantId); + } + + bool IsSynchronousModeActive() const { + + std::lock_guard SyncLock(SynchronizationMutex); + + for(auto const &SynchronizationWindow: SynchronizationWindowMap) { + if ( SynchronizationWindow.second.TargetGameTime > carla::rpc::NO_SYNC_TARGET_GAME_TIME) { + return true; + } + } + return false; + } + + carla::rpc::synchronization_target_game_time GetTargetSynchronizationTime(double const CurrentGameTime, double const RequestedDltaTime) const { + + std::lock_guard SyncLock(SynchronizationMutex); + + static int LogOncePerFrameCouter = 0; + bool LogOutput = false; + if (LogOncePerFrameCouter < FCarlaEngine::GetFrameCounter()) { + LogOutput = true; + LogOncePerFrameCouter = FCarlaEngine::GetFrameCounter(); + } + + carla::rpc::synchronization_target_game_time TargetGameTime = CurrentGameTime+RequestedDltaTime; + for(auto const &SynchronizationWindow: SynchronizationWindowMap) { + if ( (SynchronizationWindow.second.TargetGameTime > carla::rpc::NO_SYNC_TARGET_GAME_TIME) && (SynchronizationWindow.second.TargetGameTime < TargetGameTime) ) { + if (LogOutput) { + UE_LOG(LogCarla, Verbose, TEXT("ServerSynchronization::GetTargetSynchronizationTime[%s:%u] = %f"), UTF8_TO_TCHAR(SynchronizationWindow.first.c_str()), SynchronizationWindow.second.ParticipantId, SynchronizationWindow.second.TargetGameTime); + } + TargetGameTime = SynchronizationWindow.second.TargetGameTime; + } + } + if (LogOutput) { + UE_LOG(LogCarla, Verbose, TEXT("ServerSynchronization::GetTargetSynchronizationTime[ALL:ALL] = %f"), TargetGameTime); + } + return TargetGameTime; + } + + carla::rpc::Response UpdateSynchronizationWindow( + carla::rpc::synchronization_client_id_type const &ClientId, + carla::rpc::synchronization_participant_id_type const &ParticipantId, + carla::rpc::synchronization_target_game_time const &TargetGameTime) { + + std::lock_guard SyncLock(SynchronizationMutex); + + if ( ClientId != carla::rpc::ALL_CLIENTS ) { + auto const SynchronizationParticipantEqualRange = SynchronizationWindowMap.equal_range(ClientId); + bool ParticipantFound = false; + for (auto SynchronizationWindowIter=SynchronizationParticipantEqualRange.first; + SynchronizationWindowIter != SynchronizationParticipantEqualRange.second; + SynchronizationWindowIter++) { + if (SynchronizationWindowIter->second.ParticipantId == ParticipantId ) { + ParticipantFound=true; + SynchronizationWindowIter->second.TargetGameTime = TargetGameTime; + UE_LOG(LogCarla, Verbose, TEXT("ServerSynchronization::UpdateSynchronizationWindow[%s:%u] = %f"), UTF8_TO_TCHAR(ClientId.c_str()), ParticipantId, TargetGameTime); + } + } + if ( !ParticipantFound ) { + UE_LOG(LogCarla, Error, TEXT("ServerSynchronization::UpdateSynchronizationWindow[%s:%u] = %f failed."), UTF8_TO_TCHAR(ClientId.c_str()), ParticipantId, TargetGameTime); + LogSynchronizationMap("Update failed"); + return carla::rpc::ResponseError("ServerSynchronization::UpdateSynchronizationWindow did not find requested SynchronizationParticipant\n"); + } + } + else { + for (auto &SynchronizationWindow: SynchronizationWindowMap) { + if (SynchronizationWindow.second.TargetGameTime > carla::rpc::NO_SYNC_TARGET_GAME_TIME) { + SynchronizationWindow.second.TargetGameTime = TargetGameTime; + UE_LOG(LogCarla, Verbose, TEXT("ServerSynchronization::UpdateSynchronizationWindow[%s:%u] = %f FORCE"), UTF8_TO_TCHAR(SynchronizationWindow.first.c_str()), SynchronizationWindow.second.ParticipantId, TargetGameTime); + } + } + } + SyncStateChanged=true; + return true; + } + + void LogSynchronizationMap(std::string const &Reason) { + for (auto &SynchronizationWindow: SynchronizationWindowMap) { + UE_LOG(LogCarla, Verbose, TEXT("ServerSynchronization::LogSynchronizationMap[%s:%u] = %f (%s)"), UTF8_TO_TCHAR(SynchronizationWindow.first.c_str()), SynchronizationWindow.second.ParticipantId, SynchronizationWindow.second.TargetGameTime, *FString(Reason.c_str())); + } + } + + /** + * @brief Get the synchronization window participant states and a flag if they have changed since last call. + */ + std::pair > GetSynchronizationWindowParticipantStates() { + std::vector SynchronizationWindowParticipantStates; + SynchronizationWindowParticipantStates.reserve(SynchronizationWindowMap.size()); + for (auto &SynchronizationWindow: SynchronizationWindowMap) { + carla::rpc::synchronization_window_participant_state ParticipantState { + SynchronizationWindow.first, + SynchronizationWindow.second.ParticipantId, + SynchronizationWindow.second.TargetGameTime + }; + SynchronizationWindowParticipantStates.push_back(ParticipantState); + } + auto ResultChanged = SyncStateChanged; + SyncStateChanged = false; + return std::make_pair(ResultChanged, SynchronizationWindowParticipantStates); + } + +private: + mutable std::mutex SynchronizationMutex{}; + + struct SynchonizationWindow{ + carla::rpc::synchronization_participant_id_type ParticipantId; + carla::rpc::synchronization_target_game_time TargetGameTime{carla::rpc::NO_SYNC_TARGET_GAME_TIME}; + }; + + std::map ParticipantIdMaxMap; + std::multimap SynchronizationWindowMap; + bool SyncStateChanged {false}; + +}; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettings.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettings.h index d632cd450d4..50f9ae30ff3 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettings.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettings.h @@ -160,5 +160,13 @@ class CARLA_API UCarlaSettings : public UObject DisplayName = "Enable ROS2") bool ROS2 = false; + /// Default ROS2 Topic Visibility + UPROPERTY(Category = "Quality Settings/ROS2", + BlueprintReadOnly, + EditAnywhere, + config, + DisplayName = " ROS2 Topics Visible On Startup") + bool ROS2TopicVisibility = true; + /// @} }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/BoundingBoxCalculator.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/BoundingBoxCalculator.cpp index 171cac4aa7a..9852a7d95ac 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/BoundingBoxCalculator.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/BoundingBoxCalculator.cpp @@ -253,11 +253,34 @@ FBoundingBox UBoundingBoxCalculator::GetSkeletalMeshBoundingBoxFromComponent( return {Origin, Extent}; } -// TODO: update to calculate current animation pose -FBoundingBox UBoundingBoxCalculator::GetSkeletalMeshBoundingBox(const USkeletalMesh* SkeletalMesh) +TArray UBoundingBoxCalculator::GetSkeletalMeshVertices(const USkeletalMesh* SkeletalMesh) { + TArray Vertices; if(!SkeletalMesh) { + UE_LOG(LogCarla, Error, TEXT("GetSkeletalMeshBoundingBox no SkeletalMesh")); + return Vertices; + } + + // Get Vertex postion information from LOD 0 of the Skeletal Mesh + FSkeletalMeshRenderData* SkeletalMeshRenderData = SkeletalMesh->GetResourceForRendering(); + FSkeletalMeshLODRenderData& LODRenderData = SkeletalMeshRenderData->LODRenderData[0]; + FStaticMeshVertexBuffers& StaticMeshVertexBuffers = LODRenderData.StaticVertexBuffers; + FPositionVertexBuffer& FPositionVertexBuffer = StaticMeshVertexBuffers.PositionVertexBuffer; + uint32 NumVertices = FPositionVertexBuffer.GetNumVertices(); + + Vertices.Reserve(NumVertices); + for(uint32 i = 0; i < NumVertices; i++) { + Vertices.Add(FPositionVertexBuffer.VertexPosition(i)); + } + + return Vertices; +} + +// TODO: update to calculate current animation pose +FBoundingBox UBoundingBoxCalculator::GetSkeletalMeshBoundingBox(const USkeletalMesh* SkeletalMesh) +{ + if(!SkeletalMesh) { UE_LOG(LogCarla, Error, TEXT("GetSkeletalMeshBoundingBox no SkeletalMesh")); return {}; } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/BoundingBoxCalculator.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/BoundingBoxCalculator.h index b445c050799..24cfc5c5a6f 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/BoundingBoxCalculator.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/BoundingBoxCalculator.h @@ -55,6 +55,9 @@ class CARLA_API UBoundingBoxCalculator : public UBlueprintFunctionLibrary UFUNCTION(Category = "Carla Util", BlueprintCallable) static FBoundingBox GetSkeletalMeshBoundingBox(const USkeletalMesh* SkeletalMesh); + UFUNCTION(Category = "Carla Util", BlueprintCallable) + static TArray GetSkeletalMeshVertices(const USkeletalMesh* SkeletalMesh); + UFUNCTION(Category = "Carla Util", BlueprintCallable) static FBoundingBox GetStaticMeshBoundingBox(const UStaticMesh* StaticMesh); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp index 2b1463b961c..768c8ba02f6 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp @@ -193,7 +193,7 @@ void ACarlaWheeledVehicle::BeginPlay() MovementComponent->WheelSetups = NewWheelSetups; - LastPhysicsControl = GetVehiclePhysicsControl(); + LastAppliedPhysicsControl = GetVehiclePhysicsControl(); // Update physics in the Ackermann Controller AckermannController.UpdateVehiclePhysics(this); @@ -333,7 +333,7 @@ float ACarlaWheeledVehicle::GetMaximumSteerAngle() const void ACarlaWheeledVehicle::FlushVehicleControl() { - if (bAckermannControlActive) { + if (IsAckermannControlActive()) { AckermannController.UpdateVehicleState(this); AckermannController.RunLoop(InputControl.Control); } @@ -490,8 +490,8 @@ FVehiclePhysicsControl ACarlaWheeledVehicle::GetVehiclePhysicsControl() const PhysicsWheel.TireFriction = Vehicle4W->Wheels[i]->TireConfig->GetFrictionScale(); PhysicsWheel.Position = Vehicle4W->Wheels[i]->Location; } else { - if (i < LastPhysicsControl.Wheels.Num()) { - PhysicsWheel = LastPhysicsControl.Wheels[i]; + if (i < LastAppliedPhysicsControl.Wheels.Num()) { + PhysicsWheel = LastAppliedPhysicsControl.Wheels[i]; } } Wheels.Add(PhysicsWheel); @@ -570,8 +570,8 @@ FVehiclePhysicsControl ACarlaWheeledVehicle::GetVehiclePhysicsControl() const PhysicsWheel.LatStiffValue = PTireData.mLatStiffY; PhysicsWheel.LongStiffValue = PTireData.mLongitudinalStiffnessPerUnitGravity; } else { - if (i < LastPhysicsControl.Wheels.Num()) { - PhysicsWheel = LastPhysicsControl.Wheels[i]; + if (i < LastAppliedPhysicsControl.Wheels.Num()) { + PhysicsWheel = LastAppliedPhysicsControl.Wheels[i]; } } @@ -594,12 +594,12 @@ FVehicleLightState ACarlaWheeledVehicle::GetVehicleLightState() const void ACarlaWheeledVehicle::RestoreVehiclePhysicsControl() { - ApplyVehiclePhysicsControl(LastPhysicsControl); + ApplyVehiclePhysicsControl(LastAppliedPhysicsControl); } void ACarlaWheeledVehicle::ApplyVehiclePhysicsControl(const FVehiclePhysicsControl &PhysicsControl) { - LastPhysicsControl = PhysicsControl; + LastAppliedPhysicsControl = PhysicsControl; if (!bIsNWVehicle) { UWheeledVehicleMovementComponent4W *Vehicle4W = Cast( GetVehicleMovement()); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h index f5709d6b585..f0fd5facf4c 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h @@ -210,10 +210,10 @@ class CARLA_API ACarlaWheeledVehicle : public AWheeledVehicle UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) void ApplyVehicleControl(const FVehicleControl &Control, EVehicleInputPriority Priority) { - if (bAckermannControlActive) { + if (ActiveVehicleController::AckermannControl == CurrentActiveController) { AckermannController.Reset(); } - bAckermannControlActive = false; + CurrentActiveController = ActiveVehicleController::VehicleControl; if (InputControl.Priority <= Priority) { @@ -225,14 +225,14 @@ class CARLA_API ACarlaWheeledVehicle : public AWheeledVehicle UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) void ApplyVehicleAckermannControl(const FVehicleAckermannControl &AckermannControl, EVehicleInputPriority Priority) { - bAckermannControlActive = true; + CurrentActiveController = ActiveVehicleController::AckermannControl; LastAppliedAckermannControl = AckermannControl; AckermannController.SetTargetPoint(AckermannControl); } bool IsAckermannControlActive() const { - return bAckermannControlActive; + return ActiveVehicleController::AckermannControl == CurrentActiveController; } UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable) @@ -346,11 +346,14 @@ class CARLA_API ACarlaWheeledVehicle : public AWheeledVehicle } InputControl; + enum class ActiveVehicleController { + VehicleControl, + AckermannControl + } CurrentActiveController; FVehicleControl LastAppliedControl; FVehicleAckermannControl LastAppliedAckermannControl; - FVehiclePhysicsControl LastPhysicsControl; + FVehiclePhysicsControl LastAppliedPhysicsControl; - bool bAckermannControlActive = false; FAckermannController AckermannController; float RolloverBehaviorForce = 0.35; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleAckermannControl.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleAckermannControl.h index bc6b06f8e2e..ade31515e46 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleAckermannControl.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleAckermannControl.h @@ -13,6 +13,9 @@ struct CARLA_API FVehicleAckermannControl { GENERATED_BODY() + UPROPERTY(Category = "Vehicle Ackermann Control", EditAnywhere, BlueprintReadWrite) + float Timestamp = 0.0f; + UPROPERTY(Category = "Vehicle Ackermann Control", EditAnywhere, BlueprintReadWrite) float Steer = 0.0f; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleControl.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleControl.h index 173e9dcf351..066c8f2e27d 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleControl.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleControl.h @@ -13,6 +13,9 @@ struct CARLA_API FVehicleControl { GENERATED_BODY() + UPROPERTY(Category = "Vehicle Control", EditAnywhere, BlueprintReadWrite) + float Timestamp = 0.0f; + UPROPERTY(Category = "Vehicle Control", EditAnywhere, BlueprintReadWrite) float Throttle = 0.0f; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerControl.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerControl.h index 459adfd3d8c..edda31ea9bf 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerControl.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerControl.h @@ -13,6 +13,9 @@ struct CARLA_API FWalkerControl { GENERATED_BODY() + UPROPERTY(Category = "Vehicle Control", EditAnywhere, BlueprintReadWrite) + float Timestamp = 0.0f; + UPROPERTY(Category = "Walker Control", EditAnywhere, BlueprintReadWrite) FVector Direction = {1.0f, 0.0f, 0.0f}; diff --git a/Util/BuildTools/BuildLibCarla.sh b/Util/BuildTools/BuildLibCarla.sh index bec6a9be5e7..4857a6d996b 100755 --- a/Util/BuildTools/BuildLibCarla.sh +++ b/Util/BuildTools/BuildLibCarla.sh @@ -112,8 +112,9 @@ if ${REMOVE_INTERMEDIATE} ; then log "Cleaning intermediate files and folders." rm -Rf ${LIBCARLA_BUILD_SERVER_FOLDER}* ${LIBCARLA_BUILD_CLIENT_FOLDER}* - rm -Rf ${LIBCARLA_BUILD_PYTORCH_FOLDER}* ${LIBCARLA_BUILD_PYTORCH_FOLDER}* + rm -Rf ${LIBCARLA_BUILD_PYTORCH_FOLDER}* ${LIBCARLA_BUILD_FASTDDS_FOLDER}* rm -Rf ${LIBCARLA_INSTALL_SERVER_FOLDER} ${LIBCARLA_INSTALL_CLIENT_FOLDER} + fi @@ -123,12 +124,13 @@ fi # Build LibCarla for the given configuration. # -# usage: build_libcarla {Server,Client,ClientRSS} {Debug,Release} +# usage: build_libcarla {Server,ServerROS,Client,ClientRSS} {Debug,Release} # function build_libcarla { CMAKE_EXTRA_OPTIONS='' + M_ROS=false if [ $1 == Server ] ; then M_TOOLCHAIN=${LIBCPP_TOOLCHAIN_FILE} M_BUILD_FOLDER=${LIBCARLA_BUILD_SERVER_FOLDER}.$(echo "$2" | tr '[:upper:]' '[:lower:]') @@ -141,9 +143,11 @@ function build_libcarla { M_TOOLCHAIN=${LIBSTDCPP_TOOLCHAIN_FILE} M_BUILD_FOLDER=${LIBCARLA_BUILD_PYTORCH_FOLDER}.$(echo "$2" | tr '[:upper:]' '[:lower:]') M_INSTALL_FOLDER=${LIBCARLA_INSTALL_SERVER_FOLDER} - elif [ $1 == ros2 ] ; then + elif [ $1 == ServerROS ] ; then + BUILD_TYPE='Server' + M_ROS=true M_TOOLCHAIN=${LIBCPP_TOOLCHAIN_FILE} - M_BUILD_FOLDER=${LIBCARLA_FASTDDS_FOLDER}.$(echo "$2" | tr '[:upper:]' '[:lower:]') + M_BUILD_FOLDER=${LIBCARLA_BUILD_FASTDDS_FOLDER}.$(echo "$2" | tr '[:upper:]' '[:lower:]') M_INSTALL_FOLDER=${LIBCARLA_INSTALL_SERVER_FOLDER} elif [ $1 == ClientRSS ] ; then BUILD_TYPE='Client' @@ -188,6 +192,7 @@ function build_libcarla { -DCMAKE_BUILD_TYPE=${BUILD_TYPE:-$1} \ -DLIBCARLA_BUILD_DEBUG=${M_DEBUG} \ -DLIBCARLA_BUILD_RELEASE=${M_RELEASE} \ + -DLIBCARLA_USE_ROS=${M_ROS} \ -DCMAKE_TOOLCHAIN_FILE=${M_TOOLCHAIN} \ -DCMAKE_INSTALL_PREFIX=${M_INSTALL_FOLDER} \ -DCMAKE_EXPORT_COMPILE_COMMANDS=1 \ @@ -208,24 +213,22 @@ function build_libcarla { # ============================================================================== # -- Build all possible configurations ----------------------------------------- # ============================================================================== - +SERVER_VARIANT='Server' +if ${USE_ROS2}; then + SERVER_VARIANT='ServerROS' +fi if { ${BUILD_SERVER} && ${BUILD_OPTION_DEBUG}; }; then - build_libcarla Server Debug + build_libcarla ${SERVER_VARIANT} Debug fi if { ${BUILD_SERVER} && ${BUILD_OPTION_RELEASE}; }; then - build_libcarla Server Release + build_libcarla ${SERVER_VARIANT} Release if ${USE_PYTORCH} ; then build_libcarla Pytorch Release fi - - if ${USE_ROS2} ; then - build_libcarla ros2 Release - fi - fi CLIENT_VARIANT='Client' diff --git a/Util/BuildTools/BuildUE4Plugins.sh b/Util/BuildTools/BuildUE4Plugins.sh index 76ffadaae2e..2de21500835 100755 --- a/Util/BuildTools/BuildUE4Plugins.sh +++ b/Util/BuildTools/BuildUE4Plugins.sh @@ -86,7 +86,7 @@ if ${BUILD_STREETMAP} ; then git clone -b ${STREETMAP_BRANCH} ${STREETMAP_REPO} ${CARLAUE4_STREETMAP_FOLDER} fi cd ${CARLAUE4_STREETMAP_FOLDER} - git fetch + git fetch || echo "WARNING: checking status of streetmap failed. Ignoring." git checkout ${CURRENT_STREETMAP_COMMIT} fi fi diff --git a/Util/BuildTools/Setup.sh b/Util/BuildTools/Setup.sh index 9f93676bda4..4fc65debb9d 100755 --- a/Util/BuildTools/Setup.sh +++ b/Util/BuildTools/Setup.sh @@ -83,7 +83,7 @@ set(CMAKE_C_COMPILER ${CC}) set(CMAKE_CXX_COMPILER ${CXX}) # disable -Werror since the boost 1.72 doesn't compile with ad_rss without warnings (i.e. the geometry headers) -set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -std=c++14 -pthread -fPIC" CACHE STRING "" FORCE) +set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -std=c++17 -pthread -fPIC" CACHE STRING "" FORCE) set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -Wall -Wextra -Wpedantic" CACHE STRING "" FORCE) set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -Wdeprecated -Wshadow -Wuninitialized -Wunreachable-code" CACHE STRING "" FORCE) set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -Wpessimizing-move -Wold-style-cast -Wnull-dereference" CACHE STRING "" FORCE) @@ -91,7 +91,7 @@ set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -Wduplicate-enum -Wnon-virtual-dtor -Wh set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -Wconversion -Wfloat-overflow-conversion" CACHE STRING "" FORCE) # @todo These flags need to be compatible with setup.py compilation. -set(CMAKE_CXX_FLAGS_RELEASE_CLIENT "\${CMAKE_CXX_FLAGS_RELEASE} -DNDEBUG -g -fwrapv -O2 -Wall -Wstrict-prototypes -fno-strict-aliasing -Wdate-time -D_FORTIFY_SOURCE=2 -g -fstack-protector-strong -Wformat -Werror=format-security -fPIC -std=c++14 -Wno-missing-braces -DBOOST_ERROR_CODE_HEADER_ONLY" CACHE STRING "" FORCE) +set(CMAKE_CXX_FLAGS_RELEASE_CLIENT "\${CMAKE_CXX_FLAGS_RELEASE} -DNDEBUG -g -fwrapv -O2 -Wall -Wstrict-prototypes -fno-strict-aliasing -Wdate-time -D_FORTIFY_SOURCE=2 -g -fstack-protector-strong -Wformat -Werror=format-security -fPIC -std=c++17 -Wno-missing-braces -DBOOST_ERROR_CODE_HEADER_ONLY" CACHE STRING "" FORCE) EOL # -- LIBCPP_TOOLCHAIN_FILE ----------------------------------------------------- @@ -962,22 +962,24 @@ if ${USE_ROS2} ; then # cp -r ${UE4_ROOT}/Engine/Extras/ThirdPartyNotUE/SDKs/HostLinux/Linux_x64/v17_clang-10.0.1-centos7/x86_64-unknown-linux-gnu/include/c++/4.8.5/atomic ${FASTDDS_INCLUDE} # cp -r ${UE4_ROOT}/Engine/Extras/ThirdPartyNotUE/SDKs/HostLinux/Linux_x64/v17_clang-10.0.1-centos7/x86_64-unknown-linux-gnu/lib64/libatomic* ${FASTDDS_LIB} - # we have to tweak the sources a bit to be able to compile with our boost version and without exceptions + # we have to tweak the sources a bit to be able to compile with our boost version if [[ -e ${FAST_DDS_LIB_SOURCE_DIR}/thirdparty/boost/include/boost ]]; then # remove their boost includes, but keep their entry point rm -rf ${FAST_DDS_LIB_SOURCE_DIR}/thirdparty/boost/include/boost - # ensure the find boost compiles without exceptions - sed -i s/"CXX_STANDARD 11"/"CXX_STANDARD 11\n COMPILE_DEFINITIONS \"-DBOOST_NO_EXCEPTIONS\""/ ${FAST_DDS_LIB_SOURCE_DIR}/cmake/modules/FindThirdpartyBoost.cmake - sed -i s/"class ThirdpartyBoostCompileTest"/"#ifdef BOOST_NO_EXCEPTIONS\nnamespace boost {void throw_exception(std::exception const \& e) {}}\n#endif\nclass ThirdpartyBoostCompileTest"/ ${FAST_DDS_LIB_SOURCE_DIR}/thirdparty/boost/test/ThirdpartyBoostCompile_test.cpp fi mkdir -p ${FAST_DDS_LIB_SOURCE_DIR}/build pushd ${FAST_DDS_LIB_SOURCE_DIR}/build >/dev/null - # removed -DASIO_NO_EXCEPTIONS as fastdds makes usage of them. + # removed -DASIO_NO_EXCEPTIONS and -DBOOST_NO_EXCEPTIONS as fastdds makes usage of them. + # ensure to NOT disable ASIO_EXCEPTIONS and BOOST_EXCEPTIONS for DDS build! + # because these exceptions are actively deployed within FastDDS to detect e.g. if socket-addresses are already in use, etc. + # and reacts accordingly + # if we disable expections the exception is forwarded to CARLA server and the program gets finished, which is not desired + # behaviour cmake -G "Ninja" \ -DCMAKE_INSTALL_PREFIX="${FASTDDS_INSTALL_DIR}" \ -DFORCE_CXX="14" \ - -DCMAKE_CXX_FLAGS="-fPIC -std=c++14 -stdlib=libc++ -I${LLVM_INCLUDE} -Wl,-L${LLVM_LIBPATH} -DBOOST_NO_EXCEPTIONS ${UNREAL_HOSTED_CFLAGS}" \ + -DCMAKE_CXX_FLAGS="-fPIC -std=c++14 -stdlib=libc++ -I${LLVM_INCLUDE} -Wl,-L${LLVM_LIBPATH} ${UNREAL_HOSTED_CFLAGS}" \ -DBUILD_SHARED_LIBS=OFF \ -DBUILD_TESTING=OFF \ -DCOMPILE_EXAMPLES=OFF \ diff --git a/Util/BuildTools/Vars.mk b/Util/BuildTools/Vars.mk index 3cfd5512578..2d60ffe8f0c 100644 --- a/Util/BuildTools/Vars.mk +++ b/Util/BuildTools/Vars.mk @@ -16,7 +16,7 @@ CARLA_PYTHONAPI_SOURCE_FOLDER=${CARLA_PYTHONAPI_ROOT_FOLDER}/carla LIBCARLA_ROOT_FOLDER=${CURDIR}/LibCarla LIBCARLA_BUILD_SERVER_FOLDER=${CARLA_BUILD_FOLDER}/libcarla-server-build LIBCARLA_BUILD_PYTORCH_FOLDER=${CARLA_BUILD_FOLDER}/libcarla-pytorch-build -LIBCARLA_FASTDDS_FOLDER=${CARLA_BUILD_FOLDER}/libcarla-fastdds-install +LIBCARLA_BUILD_FASTDDS_FOLDER=${CARLA_BUILD_FOLDER}/libcarla-fastdds-install LIBCARLA_BUILD_CLIENT_FOLDER=${CARLA_BUILD_FOLDER}/libcarla-client-build LIBCARLA_INSTALL_SERVER_FOLDER=${CARLAUE4_PLUGIN_ROOT_FOLDER}/CarlaDependencies LIBCARLA_INSTALL_CLIENT_FOLDER=${CARLA_PYTHONAPI_SOURCE_FOLDER}/dependencies